From c1672220fd01d90f73e453b87877f7c605d7b5db Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 17 Mar 2020 00:04:33 +0000 Subject: [PATCH 0001/1454] [cron] Bump distribution date (2020-03-17) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 16f3effccc..4bb902e420 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-16" + #define STRING_DISTRIBUTION_DATE "2020-03-17" #endif /** From 40922c7da76f536632ffda809f13785ee4610632 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 18 Mar 2020 08:51:57 +1300 Subject: [PATCH 0002/1454] Fix MKS SBASE 1.6 E1 heater pin (#17191) --- Marlin/src/pins/ramps/pins_MKS_BASE_common.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h index 0406da5605..e859310bf0 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h @@ -29,7 +29,7 @@ #define BOARD_INFO_NAME "MKS BASE" #endif -#if MKS_BASE_VERSION == 14 || MKS_BASE_VERSION == 15 +#if MKS_BASE_VERSION >= 14 // // Heaters / Fans // From e5dcab8fd26e0c755969450f738b1e7a2ad21d9f Mon Sep 17 00:00:00 2001 From: Karl Andersson Date: Tue, 17 Mar 2020 21:05:12 +0100 Subject: [PATCH 0003/1454] ARMED support for TMC UART, probe temp (#17186) --- Marlin/src/pins/stm32/pins_ARMED.h | 30 ++++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/Marlin/src/pins/stm32/pins_ARMED.h b/Marlin/src/pins/stm32/pins_ARMED.h index 03f267a3a4..1e33336512 100644 --- a/Marlin/src/pins/stm32/pins_ARMED.h +++ b/Marlin/src/pins/stm32/pins_ARMED.h @@ -118,6 +118,10 @@ #define TEMP_1_PIN PC1 // Analog Input #define TEMP_BED_PIN PC2 // Analog Input +#if HOTENDS == 1 && TEMP_SENSOR_PROBE + #define TEMP_PROBE_PIN PC1 +#endif + // // Heaters / Fans // @@ -199,3 +203,29 @@ #define EXT7_PIN PD12 #define EXT8_PIN PB10 #define EXT9_PIN PB11 + +#if HAS_TMC_UART + // TMC2208/TMC2209 stepper drivers + // + // Software serial + // + #define X_SERIAL_TX_PIN EXT0_PIN + #define X_SERIAL_RX_PIN EXT0_PIN + + #define Y_SERIAL_TX_PIN EXT1_PIN + #define Y_SERIAL_RX_PIN EXT1_PIN + + #define Z_SERIAL_TX_PIN EXT2_PIN + #define Z_SERIAL_RX_PIN EXT2_PIN + + #define E0_SERIAL_TX_PIN EXT3_PIN + #define E0_SERIAL_RX_PIN EXT3_PIN + + #define E1_SERIAL_RX_PIN EXT4_PIN + #define E1_SERIAL_TX_PIN EXT4_PIN + + #define Z2_SERIAL_RX_PIN EXT4_PIN + #define Z2_SERIAL_TX_PIN EXT4_PIN + + #define TMC_BAUD_RATE 19200 +#endif From e8205af6fb131f0f8ced2a860ce721787a33f58d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 17 Mar 2020 15:05:33 -0500 Subject: [PATCH 0004/1454] Apply HAS_TMC_UART to pins files --- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 2 +- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 2 +- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 2 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 2 +- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 2 +- Marlin/src/pins/ramps/pins_FYSETC_F6_14.h | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 2 +- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 2 +- Marlin/src/pins/sam/pins_RAMPS_FD_V1.h | 2 +- Marlin/src/pins/samd/pins_RAMPS_144.h | 2 +- Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h | 2 +- Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h | 2 +- Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h | 2 +- Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h | 2 +- Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h | 2 +- Marlin/src/pins/stm32/pins_FLYF407ZG.h | 2 +- Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h | 2 +- Marlin/src/pins/stm32/pins_FYSETC_S6.h | 2 +- Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h | 2 +- Marlin/src/pins/stm32/pins_RUMBA32_MKS.h | 2 +- 23 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index d206547ab8..b1f7ecee38 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -271,7 +271,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 3bd2640665..adf726f024 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -150,7 +150,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index e9a46ba551..00c66521e6 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -175,7 +175,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 6fb38f3e46..28b94f019a 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -313,7 +313,7 @@ #endif #endif -#if MB(MKS_SBASE) && HAS_TMC220x +#if MB(MKS_SBASE) && HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index e7471f6ec6..5dc1db8f3f 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -152,7 +152,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 18c3ee992b..2303c1885c 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -120,7 +120,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index cac0868d51..7a6d283fb4 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -50,7 +50,7 @@ //#define BTN_EN1 P1_23 // EXP2.5 //#define BTN_EN2 P1_22 // EXP2.3 -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index c67f8283b7..6b7f2d582b 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -117,7 +117,7 @@ // the jumper next to the limit switch socket when using sensorless homing. // -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h index be5b92d4c1..dff4749fb7 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h @@ -29,7 +29,7 @@ #define Z_MAX_PIN 2 -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers */ diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 4ec882bcce..06b5eeafaf 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -298,7 +298,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 3b2d3c8b8d..9fc53379d5 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -99,7 +99,7 @@ #define E4_ENABLE_PIN 47 #define E4_CS_PIN E0_CS_PIN -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index 2e03504475..ee44dd7950 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -205,7 +205,7 @@ #endif // HAS_SPI_LCD -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 107ef9f57e..20da59e395 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -171,7 +171,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h index bfae524743..5d2c83e3b9 100644 --- a/Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h @@ -110,7 +110,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h index 0500c5d953..eaef0b09df 100644 --- a/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h @@ -165,7 +165,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h index f5c35bbdcd..fa555f4151 100644 --- a/Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h @@ -109,7 +109,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h index 5701dd5c56..8935da85af 100644 --- a/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h +++ b/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h @@ -30,7 +30,7 @@ /** * TMC2208/TMC2209 stepper drivers */ -#if HAS_TMC220x +#if HAS_TMC_UART // // Software serial // diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h index bdee26a51a..3376a99711 100644 --- a/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h @@ -115,7 +115,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/stm32/pins_FLYF407ZG.h b/Marlin/src/pins/stm32/pins_FLYF407ZG.h index 97aaf3fdfc..8c8ea2adc1 100644 --- a/Marlin/src/pins/stm32/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32/pins_FLYF407ZG.h @@ -196,7 +196,7 @@ // Trinamic Software Serial // -#if HAS_TMC220x +#if HAS_TMC_UART #define X_SERIAL_TX_PIN PG13 #define X_SERIAL_RX_PIN PG13 diff --git a/Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h index 5f7136c156..3e283911b4 100644 --- a/Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h +++ b/Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h @@ -38,7 +38,7 @@ #define FAN1_PIN PB0 // Fan1 -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers diff --git a/Marlin/src/pins/stm32/pins_FYSETC_S6.h b/Marlin/src/pins/stm32/pins_FYSETC_S6.h index 5bda7b1c97..d135ef0750 100644 --- a/Marlin/src/pins/stm32/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32/pins_FYSETC_S6.h @@ -107,7 +107,7 @@ #define E2_ENABLE_PIN PE3 #define E2_CS_PIN PC15 -#if HAS_TMC220x +#if HAS_TMC_UART // // TMC2208/TMC2209 stepper drivers // diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h index ec43ab8fc3..9090fb34c4 100644 --- a/Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h @@ -118,7 +118,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * diff --git a/Marlin/src/pins/stm32/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32/pins_RUMBA32_MKS.h index 8e2bb3b8af..a6bc2b49a6 100644 --- a/Marlin/src/pins/stm32/pins_RUMBA32_MKS.h +++ b/Marlin/src/pins/stm32/pins_RUMBA32_MKS.h @@ -56,7 +56,7 @@ #endif #endif -#if HAS_TMC220x +#if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers * From 1f5824247f632af71b1725f8bb41e66f55b14919 Mon Sep 17 00:00:00 2001 From: Joe Prints <33383148+JoePrints@users.noreply.github.com> Date: Tue, 17 Mar 2020 15:12:52 -0500 Subject: [PATCH 0005/1454] More decimal places for babystep / Z probe offset (#17195) --- Marlin/src/lcd/menu/menu.cpp | 4 ++-- Marlin/src/lcd/menu/menu.h | 22 +++++++++++-------- Marlin/src/lcd/menu/menu_advanced.cpp | 10 ++++----- Marlin/src/lcd/menu/menu_configuration.cpp | 8 +++---- Marlin/src/lcd/menu/menu_mixer.cpp | 2 +- Marlin/src/lcd/menu/menu_tune.cpp | 8 +++---- Marlin/src/libs/numtostr.cpp | 25 ++++++++++++++++------ Marlin/src/libs/numtostr.h | 9 +++++--- 8 files changed, 54 insertions(+), 34 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 959c1c4160..501120252a 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -193,7 +193,7 @@ DEFINE_MENU_EDIT_ITEM(uint16_3); // 123 right-justified DEFINE_MENU_EDIT_ITEM(uint16_4); // 1234 right-justified DEFINE_MENU_EDIT_ITEM(uint16_5); // 12345 right-justified DEFINE_MENU_EDIT_ITEM(float3); // 123 right-justified -DEFINE_MENU_EDIT_ITEM(float52); // _2.34, 12.34, -2.34 or 123.45, -23.45 +DEFINE_MENU_EDIT_ITEM(float42_52); // _2.34, 12.34, -2.34 or 123.45, -23.45 DEFINE_MENU_EDIT_ITEM(float43); // 1.234 DEFINE_MENU_EDIT_ITEM(float5); // 12345 right-justified DEFINE_MENU_EDIT_ITEM(float5_25); // 12345 right-justified (25 increment) @@ -428,7 +428,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_HOTEND_OFFSET_Z), ftostr54sign(hotend_offset[active_extruder].z)); #endif if (do_probe) { - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), ftostr52sign(probe.offset.z)); + MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), BABYSTEP_TO_STR(probe.offset.z)); #if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) _lcd_zoffset_overlay_gfx(probe.offset.z); #endif diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 4ba618e5ca..e9ec3b2496 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -47,14 +47,18 @@ typedef void (*selectFunc_t)(); void _lcd_zoffset_overlay_gfx(const float zvalue); #endif -#if Z_PROBE_OFFSET_RANGE_MIN >= -9 && Z_PROBE_OFFSET_RANGE_MAX <= 9 - // Only values from -9.999 to 9.999 - #define LCD_Z_OFFSET_FUNC(N) ftostr54sign(N) - #define LCD_Z_OFFSET_TYPE float43 -#else - // Values from -99.99 to 99.99 - #define LCD_Z_OFFSET_FUNC(N) ftostr52sign(N) - #define LCD_Z_OFFSET_TYPE float52 +#if HAS_BED_PROBE + #if Z_PROBE_OFFSET_RANGE_MIN >= -9 && Z_PROBE_OFFSET_RANGE_MAX <= 9 + #define LCD_Z_OFFSET_TYPE float43 // Values from -9.000 to +9.000 + #else + #define LCD_Z_OFFSET_TYPE float42_52 // Values from -99.99 to 99.99 + #endif +#endif + +#if ENABLED(BABYSTEP_ZPROBE_OFFSET) && Z_PROBE_OFFSET_RANGE_MIN >= -9 && Z_PROBE_OFFSET_RANGE_MAX <= 9 + #define BABYSTEP_TO_STR(N) ftostr43sign(N) +#elif ENABLED(BABYSTEPPING) + #define BABYSTEP_TO_STR(N) ftostr53sign(N) #endif //////////////////////////////////////////// @@ -289,7 +293,7 @@ DEFINE_MENU_EDIT_ITEM_TYPE(uint16_3 ,uint16_t ,ui16tostr3rj , 1 ); DEFINE_MENU_EDIT_ITEM_TYPE(uint16_4 ,uint16_t ,ui16tostr4rj , 0.1f ); // 1234 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(uint16_5 ,uint16_t ,ui16tostr5rj , 0.01f ); // 12345 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float3 ,float ,ftostr3 , 1 ); // 123 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(float52 ,float ,ftostr42_52 , 100 ); // _2.34, 12.34, -2.34 or 123.45, -23.45 +DEFINE_MENU_EDIT_ITEM_TYPE(float42_52 ,float ,ftostr42_52 , 100 ); // _2.34, 12.34, -2.34 or 123.45, -23.45 DEFINE_MENU_EDIT_ITEM_TYPE(float43 ,float ,ftostr43sign ,1000 ); // -1.234, _1.234, +1.234 DEFINE_MENU_EDIT_ITEM_TYPE(float5 ,float ,ftostr5rj , 1 ); // 12345 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5_25 ,float ,ftostr5rj , 0.04f ); // 12345 right-justified (25 increment) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index a4a8176d3a..ca02dc9622 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -112,10 +112,10 @@ void menu_cancelobject(); #if ENABLED(LIN_ADVANCE) #if EXTRUDERS == 1 - EDIT_ITEM(float52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); #elif EXTRUDERS > 1 LOOP_L_N(n, EXTRUDERS) - EDIT_ITEM_N(float52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); + EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif #endif @@ -257,7 +257,7 @@ void menu_cancelobject(); EDIT_ITEM(bool, MSG_AUTOTEMP, &planner.autotemp_enabled); EDIT_ITEM(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - 15); EDIT_ITEM(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - 15); - EDIT_ITEM(float52, MSG_FACTOR, &planner.autotemp_factor, 0, 10); + EDIT_ITEM(float42_52, MSG_FACTOR, &planner.autotemp_factor, 0, 10); #endif // @@ -556,10 +556,10 @@ void menu_advanced_settings() { SUBMENU(MSG_FILAMENT, menu_advanced_filament); #elif ENABLED(LIN_ADVANCE) #if EXTRUDERS == 1 - EDIT_ITEM(float52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); #elif EXTRUDERS > 1 LOOP_L_N(n, E_STEPPERS) - EDIT_ITEM_N(float52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); + EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 25b253b261..c9b9d26d66 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -138,12 +138,12 @@ void menu_advanced_settings(); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); #if ENABLED(DUAL_X_CARRIAGE) - EDIT_ITEM_FAST(float52, MSG_HOTEND_OFFSET_X, &hotend_offset[1].x, float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); + EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_X, &hotend_offset[1].x, float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); #else - EDIT_ITEM_FAST(float52, MSG_HOTEND_OFFSET_X, &hotend_offset[1].x, -99.0, 99.0, _recalc_offsets); + EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_X, &hotend_offset[1].x, -99.0, 99.0, _recalc_offsets); #endif - EDIT_ITEM_FAST(float52, MSG_HOTEND_OFFSET_Y, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); - EDIT_ITEM_FAST(float52, MSG_HOTEND_OFFSET_Z, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); + EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_Y, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); + EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_Z, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); #endif diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index a74fcb6e6a..7230320fa2 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -182,7 +182,7 @@ void lcd_mixer_mix_edit() { #if CHANNEL_MIX_EDITING LOOP_S_LE_N(n, 1, MIXING_STEPPERS) - EDIT_ITEM_FAST_N(float52, n, MSG_MIX_COMPONENT_N, &mixer.collector[n-1], 0, 10); + EDIT_ITEM_FAST_N(float42_52, n, MSG_MIX_COMPONENT_N, &mixer.collector[n-1], 0, 10); ACTION_ITEM(MSG_CYCLE_MIX, _lcd_mixer_cycle_mix); ACTION_ITEM(MSG_COMMIT_VTOOL, _lcd_mixer_commit_vtool); diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 216decf718..ac18e89df4 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -65,7 +65,7 @@ } if (ui.should_draw()) { const float spm = planner.steps_to_mm[axis]; - MenuEditItemBase::draw_edit_screen(msg, LCD_Z_OFFSET_FUNC(spm * babystep.accum)); + MenuEditItemBase::draw_edit_screen(msg, BABYSTEP_TO_STR(spm * babystep.accum)); #if ENABLED(BABYSTEP_DISPLAY_TOTAL) const bool in_view = (true #if HAS_GRAPHICAL_LCD @@ -81,7 +81,7 @@ #endif lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); lcd_put_wchar(':'); - lcd_put_u8str(LCD_Z_OFFSET_FUNC(spm * babystep.axis_total[BS_TOTAL_IND(axis)])); + lcd_put_u8str(BABYSTEP_TO_STR(spm * babystep.axis_total[BS_TOTAL_IND(axis)])); } #endif } @@ -232,10 +232,10 @@ void menu_tune() { // #if ENABLED(LIN_ADVANCE) && DISABLED(SLIM_LCD_MENUS) #if EXTRUDERS == 1 - EDIT_ITEM(float52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); #elif EXTRUDERS > 1 LOOP_L_N(n, EXTRUDERS) - EDIT_ITEM_N(float52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); + EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif #endif diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 3b641e0dd3..ac82bf16f1 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -174,9 +174,9 @@ const char* ftostr12ns(const float &f) { return &conv[3]; } -// Convert signed float to fixed-length string with 12.34 / -2.34 or 023.45 / -23.45 format +// Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const float &f) { - if (f <= -10 || f >= 100) return ftostr52(f); // need more digits + if (f <= -10 || f >= 100) return ftostr52(f); // -23.45 / 123.45 long i = (f * 1000 + (f < 0 ? -5: 5)) / 10; conv[2] = (f >= 0 && f < 10) ? ' ' : MINUSOR(i, DIGIMOD(i, 1000)); conv[3] = DIGIMOD(i, 100); @@ -198,9 +198,9 @@ const char* ftostr52(const float &f) { return &conv[1]; } -// Convert signed float to fixed-length string with 12.345 / -2.345 or 023.456 / -23.456 format -const char* ftostr43_53(const float &f) { - if (f <= -10 || f >= 100) return ftostr53(f); // need more digits +// Convert signed float to fixed-length string with 12.345 / _2.345 / -2.345 or -23.45 / 123.45 format +const char* ftostr53_63(const float &f) { + if (f <= -10 || f >= 100) return ftostr63(f); // -23.456 / 123.456 long i = (f * 10000 + (f < 0 ? -5: 5)) / 10; conv[1] = (f >= 0 && f < 10) ? ' ' : MINUSOR(i, DIGIMOD(i, 10000)); conv[2] = DIGIMOD(i, 1000); @@ -212,7 +212,7 @@ const char* ftostr43_53(const float &f) { } // Convert signed float to fixed-length string with 023.456 / -23.456 format -const char* ftostr53(const float &f) { +const char* ftostr63(const float &f) { long i = (f * 10000 + (f < 0 ? -5: 5)) / 10; conv[0] = MINUSOR(i, DIGIMOD(i, 100000)); conv[1] = DIGIMOD(i, 10000); @@ -310,6 +310,19 @@ const char* ftostr52sign(const float &f) { return conv; } +// Convert signed float to string with +12.345 format +const char* ftostr53sign(const float &f) { + long i = (f * 1000 + (f < 0 ? -5: 5)) / 10; + conv[0] = MINUSOR(i, '+'); + conv[1] = DIGIMOD(i, 10000); + conv[2] = DIGIMOD(i, 1000); + conv[3] = '.'; + conv[4] = DIGIMOD(i, 100); + conv[5] = DIGIMOD(i, 10); + conv[6] = DIGIMOD(i, 1); + return conv; +} + // Convert unsigned float to string with ____4.5, __34.5, _234.5, 1234.5 format const char* ftostr51rj(const float &f) { const long i = ((f < 0 ? -f : f) * 100 + 5) / 10; diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index d5453e8176..8b6b83391f 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -58,17 +58,17 @@ const char* i16tostr4signrj(const int16_t x); // Convert unsigned float to string with 1.23 format const char* ftostr12ns(const float &x); -// Convert signed float to fixed-length string with 12.34 / -2.34 or 023.45 / -23.45 format +// Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const float &x); // Convert signed float to fixed-length string with 023.45 / -23.45 format const char* ftostr52(const float &x); // Convert signed float to fixed-length string with 12.345 / -2.345 or 023.456 / -23.456 format -const char* ftostr43_53(const float &x); +const char* ftostr53_63(const float &x); // Convert signed float to fixed-length string with 023.456 / -23.456 format -const char* ftostr53(const float &x); +const char* ftostr63(const float &x); // Convert float to fixed-length string with +123.4 / -123.4 format const char* ftostr41sign(const float &x); @@ -91,6 +91,9 @@ const char* ftostr52sp(const float &x); // Convert signed float to string with +123.45 format const char* ftostr52sign(const float &x); +// Convert signed float to string with +12.345 format +const char* ftostr53sign(const float &f); + // Convert unsigned float to string with 1234.5 format omitting trailing zeros const char* ftostr51rj(const float &x); From c768605bde89d636cd021e953f0ee4e5d3ed025b Mon Sep 17 00:00:00 2001 From: RasmusAaen Date: Tue, 17 Mar 2020 21:25:10 +0100 Subject: [PATCH 0006/1454] Add Copymaster3D board (#17188) --- Marlin/Configuration.h | 1 + Marlin/Makefile | 2 + Marlin/src/core/boards.h | 1 + Marlin/src/module/thermistor/thermistor_202.h | 69 +++++++++++++++++++ Marlin/src/module/thermistor/thermistors.h | 3 + Marlin/src/pins/pins.h | 2 + Marlin/src/pins/ramps/pins_COPYMASTER_3D.h | 33 +++++++++ Marlin/src/pins/ramps/pins_RAMPS.h | 4 +- 8 files changed, 114 insertions(+), 1 deletion(-) create mode 100644 Marlin/src/module/thermistor/thermistor_202.h create mode 100644 Marlin/src/pins/ramps/pins_COPYMASTER_3D.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 6cac225fce..007b8fc5df 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -363,6 +363,7 @@ * 331 : (3.3V scaled thermistor 1 table for MEGA) * 332 : (3.3V scaled thermistor 1 table for DUE) * 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) + * 202 : 200k thermistor - Copymaster 3D * 3 : Mendel-parts thermistor (4.7k pullup) * 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup) diff --git a/Marlin/Makefile b/Marlin/Makefile index fcd763881e..0a9b3a45d7 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -267,6 +267,8 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1147) else ifeq ($(HARDWARE_MOTHERBOARD),1148) # MKS GEN L V2 else ifeq ($(HARDWARE_MOTHERBOARD),1149) +# Copymaster 3D +else ifeq ($(HARDWARE_MOTHERBOARD),1150) # # RAMBo and derivatives diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 09b0eada1a..86107f7d86 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -103,6 +103,7 @@ #define BOARD_HJC2560C_REV2 1147 // ADIMLab Gantry v2 #define BOARD_TANGO 1148 // BIQU Tango V1 #define BOARD_MKS_GEN_L_V2 1149 // MKS GEN L V2 +#define BOARD_COPYMASTER_3D 1150 // Copymaster 3D // // RAMBo and derivatives diff --git a/Marlin/src/module/thermistor/thermistor_202.h b/Marlin/src/module/thermistor/thermistor_202.h new file mode 100644 index 0000000000..9da3d45f45 --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_202.h @@ -0,0 +1,69 @@ +// +// Unknown 200K thermistor on a Copymaster 3D hotend +// Temptable sent from dealer technologyoutlet.co.uk +// + +const short temptable_202[][2] PROGMEM = { + { OV( 1), 864 }, + { OV( 35), 300 }, + { OV( 38), 295 }, + { OV( 41), 290 }, + { OV( 44), 285 }, + { OV( 47), 280 }, + { OV( 51), 275 }, + { OV( 55), 270 }, + { OV( 60), 265 }, + { OV( 65), 260 }, + { OV( 70), 255 }, + { OV( 76), 250 }, + { OV( 83), 245 }, + { OV( 90), 240 }, + { OV( 98), 235 }, + { OV( 107), 230 }, + { OV( 116), 225 }, + { OV( 127), 220 }, + { OV( 138), 215 }, + { OV( 151), 210 }, + { OV( 164), 205 }, + { OV( 179), 200 }, + { OV( 195), 195 }, + { OV( 213), 190 }, + { OV( 232), 185 }, + { OV( 253), 180 }, + { OV( 275), 175 }, + { OV( 299), 170 }, + { OV( 325), 165 }, + { OV( 352), 160 }, + { OV( 381), 155 }, + { OV( 411), 150 }, + { OV( 443), 145 }, + { OV( 476), 140 }, + { OV( 511), 135 }, + { OV( 546), 130 }, + { OV( 581), 125 }, + { OV( 617), 120 }, + { OV( 652), 115 }, + { OV( 687), 110 }, + { OV( 720), 105 }, + { OV( 753), 100 }, + { OV( 783), 95 }, + { OV( 812), 90 }, + { OV( 839), 85 }, + { OV( 864), 80 }, + { OV( 886), 75 }, + { OV( 906), 70 }, + { OV( 924), 65 }, + { OV( 940), 60 }, + { OV( 954), 55 }, + { OV( 966), 50 }, + { OV( 976), 45 }, + { OV( 985), 40 }, + { OV( 992), 35 }, + { OV( 998), 30 }, + { OV(1003), 25 }, + { OV(1007), 20 }, + { OV(1011), 15 }, + { OV(1014), 10 }, + { OV(1016), 5 }, + { OV(1018), 0 } +}; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 2a1500eebe..8ac9f11a55 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -151,6 +151,9 @@ #if ANY_THERMISTOR_IS(201) // Pt100 with LMV324 Overlord #include "thermistor_201.h" #endif +#if ANY_THERMISTOR_IS(202) // 200K thermistor in Copymaker3D hotend + #include "thermistor_202.h" +#endif #if ANY_THERMISTOR_IS(331) // Like table 1, but with 3V3 as input voltage for MEGA #include "thermistor_331.h" #endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 64b9e85ba8..27d9545c3f 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -188,6 +188,8 @@ #include "ramps/pins_TANGO.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_L_V2) #include "ramps/pins_MKS_GEN_L_V2.h" // ATmega2560 env:mega2560 +#elif MB(COPYMASTER_3D) + #include "ramps/pins_COPYMASTER_3D.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives diff --git a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h new file mode 100644 index 0000000000..7ee66b1194 --- /dev/null +++ b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "Copymaster 3D RAMPS" + +#define Z_STEP_PIN 47 +#define FIL_RUNOUT_PIN 15 +#define SD_DETECT_PIN 66 + +// +// Import RAMPS 1.4 pins +// +#include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 06b5eeafaf..272ff5636b 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -133,7 +133,9 @@ #define Y_CS_PIN 49 #endif -#define Z_STEP_PIN 46 +#ifndef Z_STEP_PIN + #define Z_STEP_PIN 46 +#endif #define Z_DIR_PIN 48 #define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN From 252178fe6249ab576bd9c1b542dcb289da8b161d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 18 Mar 2020 00:04:28 +0000 Subject: [PATCH 0007/1454] [cron] Bump distribution date (2020-03-18) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4bb902e420..4bae2a13df 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-17" + #define STRING_DISTRIBUTION_DATE "2020-03-18" #endif /** From abea6d5787654dc67bc86ac75207a997da9a7219 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 18 Mar 2020 10:30:19 -0500 Subject: [PATCH 0008/1454] Tweak some lambdas --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/gcode/feature/advance/M900.cpp | 2 +- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/lcd/ultralcd.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 1aad462f16..1ac036e5bc 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1611,7 +1611,7 @@ * numbers for those locations should be 0. */ #ifdef VALIDATE_MESH_TILT - auto d_from = []() { DEBUG_ECHOPGM("D from "); }; + auto d_from = []{ DEBUG_ECHOPGM("D from "); }; auto normed = [&](const xy_pos_t &pos, const float &zadd) { return normal.x * pos.x + normal.y * pos.y + zadd; }; diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 5a029cbf01..b3985401cf 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -42,7 +42,7 @@ */ void GcodeSuite::M900() { - auto echo_value_oor = [] (const char ltr, const bool ten=true) { + auto echo_value_oor = [](const char ltr, const bool ten=true) { SERIAL_CHAR('?'); SERIAL_CHAR(ltr); SERIAL_ECHOPGM(" value out of range"); if (ten) SERIAL_ECHOPGM(" (0-10)"); diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index aa35a6915c..a27e2c9726 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -103,7 +103,7 @@ void _man_probe_pt(const xy_pos_t &xy) { #endif void lcd_delta_settings() { - auto _recalc_delta_settings = []() { + auto _recalc_delta_settings = []{ #if HAS_LEVELING reset_bed_level(); // After changing kinematics bed-level data is no longer valid #endif diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 48129b61ae..1cb23baa25 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -227,7 +227,7 @@ millis_t MarlinUI::next_button_update_ms; // = 0 SETCURSOR(col, row); if (!string) return; - auto _newline = [&col, &row]() { + auto _newline = [&col, &row]{ col = 0; row++; // Move col to string len (plus space) SETCURSOR(0, row); // Simulate carriage return }; From 83eec683c969d793b473015476d03f868b470c04 Mon Sep 17 00:00:00 2001 From: Erkan Colak Date: Wed, 18 Mar 2020 19:41:12 +0100 Subject: [PATCH 0009/1454] New Controller Fan options and M710 gcode (#17149) --- Marlin/Configuration_adv.h | 19 +++-- Marlin/src/MarlinCore.cpp | 10 +-- Marlin/src/feature/controllerfan.cpp | 85 ++++++++++++------- Marlin/src/feature/controllerfan.h | 54 +++++++++++- Marlin/src/feature/power.cpp | 4 +- .../src/gcode/feature/controllerfan/M710.cpp | 83 ++++++++++++++++++ Marlin/src/gcode/gcode.cpp | 4 + Marlin/src/gcode/gcode.h | 4 + Marlin/src/inc/SanityCheck.h | 2 + Marlin/src/lcd/language/language_de.h | 5 ++ Marlin/src/lcd/language/language_en.h | 5 ++ Marlin/src/lcd/menu/menu_configuration.cpp | 25 ++++++ Marlin/src/module/configuration_store.cpp | 47 ++++++++++ buildroot/share/tests/mega2560-tests | 12 +-- 14 files changed, 307 insertions(+), 52 deletions(-) create mode 100644 Marlin/src/gcode/feature/controllerfan/M710.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6149864ab4..370fbaf6ec 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -338,15 +338,22 @@ * Controller Fan * To cool down the stepper drivers and MOSFETs. * - * The fan will turn on automatically whenever any stepper is enabled - * and turn off after a set period after all steppers are turned off. + * The fan turns on automatically whenever any driver is enabled and turns + * off (or reduces to idle speed) shortly after drivers are turned off. + * */ //#define USE_CONTROLLER_FAN #if ENABLED(USE_CONTROLLER_FAN) - //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan - #define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled - #define CONTROLLERFAN_SPEED 255 // 255 == full speed - //#define CONTROLLERFAN_SPEED_Z_ONLY 127 // Reduce noise on machines that keep Z enabled + //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan + //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered + #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) + #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled + #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled + #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors + //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings + #if ENABLED(CONTROLLER_FAN_EDITABLE) + #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu + #endif #endif // When first starting the main fan, run it at full speed for the diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5e2fe02077..0ea1a22fd8 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -567,7 +567,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { #endif #if ENABLED(USE_CONTROLLER_FAN) - controllerfan_update(); // Check if fan should be turned on to cool stepper drivers down + controllerFan.update(); // Check if fan should be turned on to cool stepper drivers down #endif #if ENABLED(AUTO_POWER_CONTROL) @@ -984,6 +984,10 @@ void setup() { SETUP_RUN(leds.setup()); #endif + #if ENABLED(USE_CONTROLLER_FAN) // Set up fan controller to initialize also the default configurations. + SETUP_RUN(controllerFan.setup()); + #endif + SETUP_RUN(ui.init()); SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.) @@ -1047,10 +1051,6 @@ void setup() { SETUP_RUN(endstops.enable_z_probe(false)); #endif - #if ENABLED(USE_CONTROLLER_FAN) - SET_OUTPUT(CONTROLLER_FAN_PIN); - #endif - #if HAS_STEPPER_RESET SETUP_RUN(enableStepperDrivers()); #endif diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index b9d8c39460..ed7fca1fe7 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -24,60 +24,79 @@ #if ENABLED(USE_CONTROLLER_FAN) +#include "controllerfan.h" #include "../module/stepper/indirection.h" #include "../module/temperature.h" -uint8_t controllerfan_speed; +ControllerFan controllerFan; -void controllerfan_update() { - static millis_t lastMotorOn = 0, // Last time a motor was turned on +uint8_t ControllerFan::speed; + +#if ENABLED(CONTROLLER_FAN_EDITABLE) + controllerFan_settings_t ControllerFan::settings; // {0} +#endif + +void ControllerFan::setup() { + SET_OUTPUT(CONTROLLER_FAN_PIN); + init(); +} + +void ControllerFan::set_fan_speed(const uint8_t s) { + speed = s < (CONTROLLERFAN_SPEED_MIN) ? 0 : s; // Fan OFF below minimum +} + +void ControllerFan::update() { + static millis_t lastMotorOn = 0, // Last time a motor was turned on nextMotorCheck = 0; // Last time the state was checked const millis_t ms = millis(); if (ELAPSED(ms, nextMotorCheck)) { nextMotorCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s - const bool xory = X_ENABLE_READ() == bool(X_ENABLE_ON) || Y_ENABLE_READ() == bool(Y_ENABLE_ON); + #define MOTOR_IS_ON(A,B) (A##_ENABLE_READ() == bool(B##_ENABLE_ON)) + #define _OR_ENABLED_E(N) || MOTOR_IS_ON(E##N,E) + + const bool + xy_motor_on = MOTOR_IS_ON(X,X) || MOTOR_IS_ON(Y,Y) + #if HAS_X2_ENABLE + || MOTOR_IS_ON(X2,X) + #endif + #if HAS_Y2_ENABLE + || MOTOR_IS_ON(Y2,Y) + #endif + , + z_motor_on = MOTOR_IS_ON(Z,Z) + #if HAS_Z2_ENABLE + || MOTOR_IS_ON(Z2,Z) + #endif + #if HAS_Z3_ENABLE + || MOTOR_IS_ON(Z3,Z) + #endif + #if HAS_Z4_ENABLE + || MOTOR_IS_ON(Z4,Z) + #endif + ; // If any of the drivers or the bed are enabled... - if (xory || Z_ENABLE_READ() == bool(Z_ENABLE_ON) + if (xy_motor_on || z_motor_on #if HAS_HEATED_BED || thermalManager.temp_bed.soft_pwm_amount > 0 #endif - #if HAS_X2_ENABLE - || X2_ENABLE_READ() == bool(X_ENABLE_ON) - #endif - #if HAS_Y2_ENABLE - || Y2_ENABLE_READ() == bool(Y_ENABLE_ON) - #endif - #if HAS_Z2_ENABLE - || Z2_ENABLE_READ() == bool(Z_ENABLE_ON) - #endif - #if HAS_Z3_ENABLE - || Z3_ENABLE_READ() == bool(Z_ENABLE_ON) - #endif - #if HAS_Z4_ENABLE - || Z4_ENABLE_READ() == bool(Z_ENABLE_ON) - #endif #if E_STEPPERS - #define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == bool(E_ENABLE_ON) REPEAT(E_STEPPERS, _OR_ENABLED_E) #endif - ) { - lastMotorOn = ms; //... set time to NOW so the fan will turn on - } + ) lastMotorOn = ms; //... set time to NOW so the fan will turn on - // Fan off if no steppers have been enabled for CONTROLLERFAN_SECS seconds - controllerfan_speed = (!lastMotorOn || ELAPSED(ms, lastMotorOn + (CONTROLLERFAN_SECS) * 1000UL)) ? 0 : ( - #ifdef CONTROLLERFAN_SPEED_Z_ONLY - xory ? CONTROLLERFAN_SPEED : CONTROLLERFAN_SPEED_Z_ONLY - #else - CONTROLLERFAN_SPEED - #endif + // Fan Settings. Set fan > 0: + // - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds. + // - If System is on idle and idle fan speed settings is activated. + set_fan_speed( + settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + settings.duration * 1000UL) + ? settings.active_speed : settings.idle_speed ); // Allow digital or PWM fan output (see M42 handling) - WRITE(CONTROLLER_FAN_PIN, controllerfan_speed); - analogWrite(pin_t(CONTROLLER_FAN_PIN), controllerfan_speed); + WRITE(CONTROLLER_FAN_PIN, speed); + analogWrite(pin_t(CONTROLLER_FAN_PIN), speed); } } diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index f2facc288f..bc48a6e261 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -21,4 +21,56 @@ */ #pragma once -void controllerfan_update(); +#include "../inc/MarlinConfigPre.h" + +typedef struct { + uint8_t active_speed, // 0-255 (fullspeed); Speed with enabled stepper motors + idle_speed; // 0-255 (fullspeed); Speed after idle period with all motors are disabled + uint16_t duration; // Duration in seconds for the fan to run after all motors are disabled + bool auto_mode; // Default true +} controllerFan_settings_t; + +#ifndef CONTROLLERFAN_SPEED_ACTIVE + #define CONTROLLERFAN_SPEED_ACTIVE 255 +#endif +#ifndef CONTROLLERFAN_SPEED_IDLE + #define CONTROLLERFAN_SPEED_IDLE 0 +#endif +#ifndef CONTROLLERFAN_IDLE_TIME + #define CONTROLLERFAN_IDLE_TIME 60 +#endif + +static constexpr controllerFan_settings_t controllerFan_defaults = { + CONTROLLERFAN_SPEED_ACTIVE, + CONTROLLERFAN_SPEED_IDLE, + CONTROLLERFAN_IDLE_TIME, + true +}; + +#if ENABLED(USE_CONTROLLER_FAN) + +class ControllerFan { + private: + static uint8_t speed; + static void set_fan_speed(const uint8_t s); + + public: + #if ENABLED(CONTROLLER_FAN_EDITABLE) + static controllerFan_settings_t settings; + #else + static const controllerFan_settings_t &settings = controllerFan_defaults; + #endif + static inline bool state() { return speed > 0; } + static inline void init() { reset(); } + static inline void reset() { + #if ENABLED(CONTROLLER_FAN_EDITABLE) + settings = controllerFan_defaults; + #endif + } + static void setup(); + static void update(); +}; + +extern ControllerFan controllerFan; + +#endif diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index cf18e2130c..1fa751811e 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -46,8 +46,8 @@ bool Power::is_power_needed() { HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true; #endif - #if ENABLED(AUTO_POWER_CONTROLLERFAN, USE_CONTROLLER_FAN) && HAS_CONTROLLER_FAN - if (controllerfan_speed) return true; + #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + if (controllerFan.state()) return true; #endif #if ENABLED(AUTO_POWER_CHAMBER_FAN) diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp new file mode 100644 index 0000000000..8e5845fa85 --- /dev/null +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -0,0 +1,83 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(CONTROLLER_FAN_EDITABLE) + +#include "../../gcode.h" +#include "../../../feature/controllerfan.h" + +void M710_report(const bool forReplay) { + if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); } + SERIAL_ECHOLNPAIR("M710 " + "S", int(controllerFan.settings.active_speed), + "I", int(controllerFan.settings.idle_speed), + "A", int(controllerFan.settings.auto_mode), + "D", controllerFan.settings.duration, + " ; (", (int(controllerFan.settings.active_speed) * 100) / 255, "%" + " ", (int(controllerFan.settings.idle_speed) * 100) / 255, "%)" + ); +} + +/** + * M710: Set controller fan settings + * + * R : Reset to defaults + * S[0-255] : Fan speed when motors are active + * I[0-255] : Fan speed when motors are idle + * A[0|1] : Turn auto mode on or off + * D : Set auto mode idle duration + * + * Examples: + * M710 ; Report current Settings + * M710 R ; Reset SIAD to defaults + * M710 I64 ; Set controller fan Idle Speed to 25% + * M710 S255 ; Set controller fan Active Speed to 100% + * M710 S0 ; Set controller fan Active Speed to OFF + * M710 I255 A0 ; Set controller fan Idle Speed to 100% with Auto Mode OFF + * M710 I127 A1 S255 D160 ; Set controller fan idle speed 50%, AutoMode On, Fan speed 100%, duration to 160 Secs + */ +void GcodeSuite::M710() { + + const bool seenR = parser.seen('R'); + if (seenR) controllerFan.reset(); + + const bool seenS = parser.seenval('S'); + if (seenS) controllerFan.settings.active_speed = parser.value_byte(); + + const bool seenI = parser.seenval('I'); + if (seenI) controllerFan.settings.idle_speed = parser.value_byte(); + + const bool seenA = parser.seenval('A'); + if (seenA) controllerFan.settings.auto_mode = parser.value_bool(); + + const bool seenD = parser.seenval('D'); + if (seenD) controllerFan.settings.duration = parser.value_ushort(); + + if (seenR || seenS || seenI || seenA || seenD) + controllerFan.update(); + else + M710_report(false); +} + +#endif // CONTROLLER_FAN_EDITABLE diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 266361a099..1ce1e3d5cb 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -752,6 +752,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 702: M702(); break; // M702: Unload Filament #endif + #if ENABLED(CONTROLLER_FAN_EDITABLE) + case 710: M710(); break; // M710: Set Controller Fan settings + #endif + #if ENABLED(GCODE_MACROS) case 810: case 811: case 812: case 813: case 814: case 815: case 816: case 817: case 818: case 819: diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 27a038dde9..c1024ac440 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -972,6 +972,10 @@ private: static void M7219(); #endif + #if ENABLED(CONTROLLER_FAN_EDITABLE) + static void M710(); + #endif + static void T(const uint8_t tool_index); }; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 574d6a336e..89b53362d6 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -270,6 +270,8 @@ #error "Replace SLED_PIN with SOL1_PIN (applies to both Z_PROBE_SLED and SOLENOID_PROBE)." #elif defined(CONTROLLERFAN_PIN) #error "CONTROLLERFAN_PIN is now CONTROLLER_FAN_PIN, enabled with USE_CONTROLLER_FAN. Please update your Configuration_adv.h." +#elif defined(CONTROLLERFAN_SPEED) + #error "CONTROLLERFAN_SPEED is now CONTROLLERFAN_SPEED_ACTIVE. Please update your Configuration_adv.h." #elif defined(MIN_RETRACT) #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT. Please update your Configuration_adv.h." #elif defined(ADVANCE) diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 5ac8ee04da..cd201ded34 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -236,6 +236,11 @@ namespace Language_de { PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Lüfter ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Geschw. Extralüfter"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Geschw. Extralüfter ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Lüfter Kontroller"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Lüfter Leerlauf"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Motorlast Modus"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Lüfter Motorlast"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Ausschalt Delay"); PROGMEM Language_Str MSG_FLOW = _UxGT("Flussrate"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flussrate ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Einstellungen"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index b5f508973d..75c13de9c7 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -247,6 +247,11 @@ namespace Language_en { PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fan Speed"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fan Speed ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controller Fan"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); PROGMEM Language_Str MSG_FLOW = _UxGT("Flow"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flow ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index c9b9d26d66..59c80b1af0 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -227,6 +227,24 @@ void menu_advanced_settings(); } #endif +#if ENABLED(CONTROLLER_FAN_MENU) + + #include "../../feature/controllerfan.h" + + void menu_controller_fan() { + START_MENU(); + BACK_ITEM(MSG_CONFIGURATION); + EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_IDLE_SPEED, &controllerFan.settings.idle_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255, controllerFan.update); + EDIT_ITEM(bool, MSG_CONTROLLER_FAN_AUTO_ON, &controllerFan.settings.auto_mode, controllerFan.update); + if (controllerFan.settings.auto_mode) { + EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_SPEED, &controllerFan.settings.active_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255, controllerFan.update); + EDIT_ITEM(uint16_4, MSG_CONTROLLER_FAN_DURATION, &controllerFan.settings.duration, 0, 4800, controllerFan.update); + } + END_MENU(); + } + +#endif + #if ENABLED(CASE_LIGHT_MENU) #include "../../feature/caselight.h" @@ -320,6 +338,13 @@ void menu_configuration() { EDIT_ITEM(LCD_Z_OFFSET_TYPE, MSG_ZPROBE_ZOFFSET, &probe.offset.z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif + // + // Set Fan Controller speed + // + #if ENABLED(CONTROLLER_FAN_MENU) + SUBMENU(MSG_CONTROLLER_FAN, menu_controller_fan); + #endif + const bool busy = printer_busy(); if (!busy) { #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 3a83dd7c1d..4b7946c6a9 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -122,6 +122,11 @@ #include "../feature/probe_temp_comp.h" #endif +#include "../feature/controllerfan.h" +#if ENABLED(CONTROLLER_FAN_EDITABLE) + void M710_report(const bool forReplay); +#endif + #pragma pack(push, 1) // No padding between variables typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t; @@ -292,6 +297,11 @@ typedef struct SettingsDataStruct { // int16_t lcd_contrast; // M250 C + // + // Controller fan settings + // + controllerFan_settings_t controllerFan_settings; // M710 + // // POWER_LOSS_RECOVERY // @@ -880,6 +890,19 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(lcd_contrast); } + // + // Controller Fan + // + { + _FIELD_TEST(controllerFan_settings); + #if ENABLED(USE_CONTROLLER_FAN) + const controllerFan_settings_t &cfs = controllerFan.settings; + #else + controllerFan_settings_t cfs = controllerFan_defaults; + #endif + EEPROM_WRITE(cfs); + } + // // Power-Loss Recovery // @@ -1719,6 +1742,19 @@ void MarlinSettings::postprocess() { #endif } + // + // Controller Fan + // + { + _FIELD_TEST(controllerFan_settings); + #if ENABLED(CONTROLLER_FAN_EDITABLE) + const controllerFan_settings_t &cfs = controllerFan.settings; + #else + controllerFan_settings_t cfs = { 0 }; + #endif + EEPROM_READ(cfs); + } + // // Power-Loss Recovery // @@ -2590,6 +2626,13 @@ void MarlinSettings::reset() { ui.set_contrast(DEFAULT_LCD_CONTRAST); #endif + // + // Controller Fan + // + #if ENABLED(USE_CONTROLLER_FAN) + controllerFan.reset(); + #endif + // // Power-Loss Recovery // @@ -3154,6 +3197,10 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" M250 C", ui.contrast); #endif + #if ENABLED(CONTROLLER_FAN_EDITABLE) + M710_report(forReplay); + #endif + #if ENABLED(POWER_LOSS_RECOVERY) CONFIG_ECHO_HEADING("Power-Loss Recovery:"); CONFIG_ECHO_START(); diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index f120cdd6ea..0bedfd5a73 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -115,21 +115,23 @@ exec_test $1 $2 "RAMPS | ZONESTAR_LCD | MMU2 | Servo Probe | ABL 3-Pt | Debug Le # Test MINIRAMBO with PWM_MOTOR_CURRENT and many features # restore_configs -opt_set MOTHERBOARD BOARD_MINIRAMBO +opt_set MOTHERBOARD BOARD_MEGACONTROLLER opt_set LCD_LANGUAGE de opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT \ - ULTIMAKERCONTROLLER SDSUPPORT PCA9632 LCD_INFO_MENU \ + MINIPANEL SDSUPPORT PCA9632 LCD_INFO_MENU \ AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY LCD_BED_LEVELING G26_MESH_VALIDATION MESH_EDIT_MENU \ - LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ + LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT EXPERIMENTAL_I2CBUS M100_FREE_MEMORY_WATCHER \ NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE \ ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE ADVANCED_PAUSE_CONTINUOUS_PURGE FILAMENT_LOAD_UNLOAD_GCODES \ - PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL + PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL \ + USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE +opt_set CONTROLLERFAN_SPEED_IDLE 128 opt_add M100_FREE_MEMORY_DUMPER opt_add M100_FREE_MEMORY_CORRUPTOR opt_set PWM_MOTOR_CURRENT "{ 1300, 1300, 1250 }" opt_set I2C_SLAVE_ADDRESS 63 -exec_test $1 $2 "MINIRAMBO | Ultimaker LCD | M100 | PWM_MOTOR_CURRENT | PRINTCOUNTER | Advanced Pause ..." +exec_test $1 $2 "MEGACONTROLLER | Ultimaker LCD | M100 | PWM_MOTOR_CURRENT | PRINTCOUNTER | Advanced Pause ..." # # Mixing Extruder with 5 steppers, Cyrillic From de45ac41ad175dafa799c15a85c05b812f284b42 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 18 Mar 2020 14:35:52 -0500 Subject: [PATCH 0010/1454] Implement CONTROLLER_FAN_USE_Z_ONLY Followup to #17149 --- Marlin/src/feature/controllerfan.cpp | 51 ++++++++++--------- .../src/gcode/feature/controllerfan/M710.cpp | 4 +- Marlin/src/lcd/menu/menu_configuration.cpp | 8 +-- 3 files changed, 31 insertions(+), 32 deletions(-) diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index ed7fca1fe7..0746700407 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -55,35 +55,36 @@ void ControllerFan::update() { #define MOTOR_IS_ON(A,B) (A##_ENABLE_READ() == bool(B##_ENABLE_ON)) #define _OR_ENABLED_E(N) || MOTOR_IS_ON(E##N,E) - const bool - xy_motor_on = MOTOR_IS_ON(X,X) || MOTOR_IS_ON(Y,Y) - #if HAS_X2_ENABLE - || MOTOR_IS_ON(X2,X) - #endif - #if HAS_Y2_ENABLE - || MOTOR_IS_ON(Y2,Y) - #endif - , - z_motor_on = MOTOR_IS_ON(Z,Z) - #if HAS_Z2_ENABLE - || MOTOR_IS_ON(Z2,Z) - #endif - #if HAS_Z3_ENABLE - || MOTOR_IS_ON(Z3,Z) - #endif - #if HAS_Z4_ENABLE - || MOTOR_IS_ON(Z4,Z) - #endif - ; + const bool motor_on = MOTOR_IS_ON(Z,Z) + #if HAS_Z2_ENABLE + || MOTOR_IS_ON(Z2,Z) + #endif + #if HAS_Z3_ENABLE + || MOTOR_IS_ON(Z3,Z) + #endif + #if HAS_Z4_ENABLE + || MOTOR_IS_ON(Z4,Z) + #endif + || (DISABLED(CONTROLLER_FAN_USE_Z_ONLY) && ( + MOTOR_IS_ON(X,X) || MOTOR_IS_ON(Y,Y) + #if HAS_X2_ENABLE + || MOTOR_IS_ON(X2,X) + #endif + #if HAS_Y2_ENABLE + || MOTOR_IS_ON(Y2,Y) + #endif + #if E_STEPPERS + REPEAT(E_STEPPERS, _OR_ENABLED_E) + #endif + ) + ) + ; - // If any of the drivers or the bed are enabled... - if (xy_motor_on || z_motor_on + // If any of the drivers or the heated bed are enabled... + if (motor_on #if HAS_HEATED_BED || thermalManager.temp_bed.soft_pwm_amount > 0 #endif - #if E_STEPPERS - REPEAT(E_STEPPERS, _OR_ENABLED_E) - #endif ) lastMotorOn = ms; //... set time to NOW so the fan will turn on // Fan Settings. Set fan > 0: diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index 8e5845fa85..e00fa77d62 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -74,9 +74,7 @@ void GcodeSuite::M710() { const bool seenD = parser.seenval('D'); if (seenD) controllerFan.settings.duration = parser.value_ushort(); - if (seenR || seenS || seenI || seenA || seenD) - controllerFan.update(); - else + if (!(seenR || seenS || seenI || seenA || seenD)) M710_report(false); } diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 59c80b1af0..6dbc680659 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -234,11 +234,11 @@ void menu_advanced_settings(); void menu_controller_fan() { START_MENU(); BACK_ITEM(MSG_CONFIGURATION); - EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_IDLE_SPEED, &controllerFan.settings.idle_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255, controllerFan.update); - EDIT_ITEM(bool, MSG_CONTROLLER_FAN_AUTO_ON, &controllerFan.settings.auto_mode, controllerFan.update); + EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_IDLE_SPEED, &controllerFan.settings.idle_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255); + EDIT_ITEM(bool, MSG_CONTROLLER_FAN_AUTO_ON, &controllerFan.settings.auto_mode); if (controllerFan.settings.auto_mode) { - EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_SPEED, &controllerFan.settings.active_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255, controllerFan.update); - EDIT_ITEM(uint16_4, MSG_CONTROLLER_FAN_DURATION, &controllerFan.settings.duration, 0, 4800, controllerFan.update); + EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_SPEED, &controllerFan.settings.active_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255); + EDIT_ITEM(uint16_4, MSG_CONTROLLER_FAN_DURATION, &controllerFan.settings.duration, 0, 4800); } END_MENU(); } From 84dec5da1065e1d506d2b4bd18294e5837ebe976 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Wed, 18 Mar 2020 17:12:51 -0400 Subject: [PATCH 0011/1454] Add M42 M, improve M43 (#17173) --- Marlin/src/gcode/config/M43.cpp | 2 ++ Marlin/src/gcode/control/M42.cpp | 25 ++++++++++++++++++++----- 2 files changed, 22 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 661c413191..2c28da62fb 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -67,6 +67,7 @@ inline void toggle_pins() { else { watchdog_refresh(); report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing ")); + const bool prior_mode = GET_PINMODE(pin); #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO if (pin == TEENSY_E2) { SET_OUTPUT(TEENSY_E2); @@ -95,6 +96,7 @@ inline void toggle_pins() { watchdog_refresh(); } } + pinMode(pin, prior_mode); } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 7106ce5502..74625b0318 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -37,16 +37,33 @@ * * S Pin status from 0 - 255 * I Flag to ignore Marlin's pin protection + * + * M Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN */ void GcodeSuite::M42() { - if (!parser.seenval('S')) return; - const byte pin_status = parser.value_byte(); - const int pin_index = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN)); if (pin_index < 0) return; const pin_t pin = GET_PIN_MAP_PIN(pin_index); + if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); + + if (parser.seenval('M')) { + switch (parser.value_byte()) { + case 0: pinMode(pin, INPUT); break; + case 1: pinMode(pin, OUTPUT); break; + case 2: pinMode(pin, INPUT_PULLUP); break; + #ifdef INPUT_PULLDOWN + case 3: pinMode(pin, INPUT_PULLDOWN); break; + #endif + default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); + } + return; + } + + if (!parser.seenval('S')) return; + const byte pin_status = parser.value_byte(); + #if FAN_COUNT > 0 switch (pin) { #if HAS_FAN0 @@ -76,8 +93,6 @@ void GcodeSuite::M42() { } #endif - if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); - pinMode(pin, OUTPUT); extDigitalWrite(pin, pin_status); analogWrite(pin, pin_status); From 14daf1ee5ea831e0c7229988c9aeeeb5069e8337 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 19 Mar 2020 00:03:40 +0000 Subject: [PATCH 0012/1454] [cron] Bump distribution date (2020-03-19) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4bae2a13df..c54f012736 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-18" + #define STRING_DISTRIBUTION_DATE "2020-03-19" #endif /** From 71db5c16055c2d68c6fda8a6a2192e428538f8b7 Mon Sep 17 00:00:00 2001 From: George Fu Date: Fri, 20 Mar 2020 03:11:55 +0800 Subject: [PATCH 0013/1454] Fix FYSETC mini 12864 init / glitches (#17209) --- Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp index e6fc310df1..94956e7410 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp @@ -118,7 +118,7 @@ static const uint8_t u8g_dev_uc1701_mini12864_HAL_init_seq[] PROGMEM = { static const uint8_t u8g_dev_uc1701_mini12864_HAL_data_start[] PROGMEM = { U8G_ESC_ADR(0), // instruction mode U8G_ESC_CS(1), // enable chip - #if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY, FYSETC_MINI_12864) UC1701_START_LINE(0), // set display start line to 0 UC1701_ADC_REVERSE(0), // ADC set to reverse UC1701_OUT_MODE(1), // common output mode From 1738c13bc27f7cc233fc99217348c8e0413191dd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 20 Mar 2020 00:03:07 +0000 Subject: [PATCH 0014/1454] [cron] Bump distribution date (2020-03-20) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c54f012736..fddda1557d 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-19" + #define STRING_DISTRIBUTION_DATE "2020-03-20" #endif /** From 3151856e981a14e836074e70836c780e93a2be55 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 21 Mar 2020 00:03:28 +0000 Subject: [PATCH 0015/1454] [cron] Bump distribution date (2020-03-21) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fddda1557d..e6d77e842c 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-20" + #define STRING_DISTRIBUTION_DATE "2020-03-21" #endif /** From 04cea864bcc197a91a162f8cc48cd6588260f8af Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 20 Mar 2020 23:45:00 -0500 Subject: [PATCH 0016/1454] Split up STM32 pins files (#17212) --- Marlin/src/pins/pins.h | 84 +++++++++---------- .../{stm32 => stm32f1}/pins_BTT_SKR_E3_DIP.h | 0 .../{stm32 => stm32f1}/pins_BTT_SKR_MINI_E3.h | 0 .../pins_BTT_SKR_MINI_E3_V1_0.h | 0 .../pins_BTT_SKR_MINI_E3_V1_2.h | 0 .../pins_BTT_SKR_MINI_V1_1.h | 0 .../pins/{stm32 => stm32f1}/pins_CHITU3D.h | 0 .../{stm32 => stm32f1}/pins_FYSETC_AIO_II.h | 0 .../{stm32 => stm32f1}/pins_FYSETC_CHEETAH.h | 0 .../pins_FYSETC_CHEETAH_V12.h | 0 .../pins/{stm32 => stm32f1}/pins_GTM32_MINI.h | 0 .../{stm32 => stm32f1}/pins_GTM32_MINI_A30.h | 0 .../{stm32 => stm32f1}/pins_GTM32_PRO_VB.h | 0 .../{stm32 => stm32f1}/pins_GTM32_REV_B.h | 0 .../{stm32 => stm32f1}/pins_JGAURORA_A5S_A1.h | 0 .../{stm32 => stm32f1}/pins_LONGER3D_LK.h | 0 .../{stm32 => stm32f1}/pins_MALYAN_M200.h | 0 .../pins/{stm32 => stm32f1}/pins_MKS_ROBIN.h | 0 .../{stm32 => stm32f1}/pins_MKS_ROBIN_LITE.h | 0 .../{stm32 => stm32f1}/pins_MKS_ROBIN_LITE3.h | 0 .../{stm32 => stm32f1}/pins_MKS_ROBIN_MINI.h | 0 .../{stm32 => stm32f1}/pins_MKS_ROBIN_NANO.h | 0 .../{stm32 => stm32f1}/pins_MKS_ROBIN_PRO.h | 0 .../pins/{stm32 => stm32f1}/pins_MORPHEUS.h | 0 .../pins/{stm32 => stm32f1}/pins_STM32F1R.h | 0 .../pins/{stm32 => stm32f1}/pins_STM3R_MINI.h | 0 .../src/pins/{stm32 => stm32f4}/pins_ARMED.h | 0 .../src/pins/{stm32 => stm32f4}/pins_BEAST.h | 0 .../pins_BLACK_STM32F407VE.h | 0 .../{stm32 => stm32f4}/pins_BTT_BTT002_V1_0.h | 0 .../{stm32 => stm32f4}/pins_BTT_GTR_V1_0.h | 0 .../pins_BTT_SKR_PRO_V1_1.h | 0 .../pins/{stm32 => stm32f4}/pins_FLYF407ZG.h | 0 .../pins/{stm32 => stm32f4}/pins_FYSETC_S6.h | 0 .../{stm32 => stm32f4}/pins_GENERIC_STM32F4.h | 0 .../pins/{stm32 => stm32f4}/pins_LERDGE_K.h | 0 .../pins/{stm32 => stm32f4}/pins_LERDGE_X.h | 0 .../pins/{stm32 => stm32f4}/pins_MKS_ROBIN2.h | 0 .../{stm32 => stm32f4}/pins_RUMBA32_AUS3D.h | 0 .../{stm32 => stm32f4}/pins_RUMBA32_MKS.h | 0 .../{stm32 => stm32f4}/pins_RUMBA32_common.h | 0 .../{stm32 => stm32f4}/pins_STEVAL_3DP001V1.h | 0 .../pins/{stm32 => stm32f4}/pins_VAKE403D.h | 0 .../pins/{stm32 => stm32f7}/pins_REMRAM_V1.h | 0 .../pins/{stm32 => stm32f7}/pins_THE_BORG.h | 0 45 files changed, 42 insertions(+), 42 deletions(-) rename Marlin/src/pins/{stm32 => stm32f1}/pins_BTT_SKR_E3_DIP.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_BTT_SKR_MINI_E3.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_BTT_SKR_MINI_E3_V1_0.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_BTT_SKR_MINI_E3_V1_2.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_BTT_SKR_MINI_V1_1.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_CHITU3D.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_FYSETC_AIO_II.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_FYSETC_CHEETAH.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_FYSETC_CHEETAH_V12.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_GTM32_MINI.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_GTM32_MINI_A30.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_GTM32_PRO_VB.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_GTM32_REV_B.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_JGAURORA_A5S_A1.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_LONGER3D_LK.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MALYAN_M200.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MKS_ROBIN.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MKS_ROBIN_LITE.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MKS_ROBIN_LITE3.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MKS_ROBIN_MINI.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MKS_ROBIN_NANO.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MKS_ROBIN_PRO.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_MORPHEUS.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_STM32F1R.h (100%) rename Marlin/src/pins/{stm32 => stm32f1}/pins_STM3R_MINI.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_ARMED.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_BEAST.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_BLACK_STM32F407VE.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_BTT_BTT002_V1_0.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_BTT_GTR_V1_0.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_BTT_SKR_PRO_V1_1.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_FLYF407ZG.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_FYSETC_S6.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_GENERIC_STM32F4.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_LERDGE_K.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_LERDGE_X.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_MKS_ROBIN2.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_RUMBA32_AUS3D.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_RUMBA32_MKS.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_RUMBA32_common.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_STEVAL_3DP001V1.h (100%) rename Marlin/src/pins/{stm32 => stm32f4}/pins_VAKE403D.h (100%) rename Marlin/src/pins/{stm32 => stm32f7}/pins_REMRAM_V1.h (100%) rename Marlin/src/pins/{stm32 => stm32f7}/pins_THE_BORG.h (100%) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 27d9545c3f..b43ba1cbc6 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -467,53 +467,53 @@ // #elif MB(STM32F103RE) - #include "stm32/pins_STM32F1R.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM32F1R.h" // STM32F1 env:STM32F103RE #elif MB(MALYAN_M200) - #include "stm32/pins_MALYAN_M200.h" // STM32F1 env:STM32F103CB_malyan + #include "stm32f1/pins_MALYAN_M200.h" // STM32F1 env:STM32F103CB_malyan #elif MB(STM3R_MINI) - #include "stm32/pins_STM3R_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM3R_MINI.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_PRO_VB) - #include "stm32/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_MINI_A30) - #include "stm32/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_MINI) - #include "stm32/pins_GTM32_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_REV_B) - #include "stm32/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103RE #elif MB(MORPHEUS) - #include "stm32/pins_MORPHEUS.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_MORPHEUS.h" // STM32F1 env:STM32F103RE #elif MB(CHITU3D) - #include "stm32/pins_CHITU3D.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_CHITU3D.h" // STM32F1 env:STM32F103RE #elif MB(MKS_ROBIN) - #include "stm32/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin + #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin #elif MB(MKS_ROBIN_MINI) - #include "stm32/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini + #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini #elif MB(MKS_ROBIN_NANO) - #include "stm32/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano + #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano #elif MB(MKS_ROBIN_LITE) - #include "stm32/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite + #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V1_0) - #include "stm32/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V1_2) - #include "stm32/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_E3_DIP) - #include "stm32/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(JGAURORA_A5S_A1) - #include "stm32/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 + #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 #elif MB(FYSETC_AIO_II) - #include "stm32/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103RC_fysetc + #include "stm32f1/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103RC_fysetc #elif MB(FYSETC_CHEETAH) - #include "stm32/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103RC_fysetc + #include "stm32f1/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103RC_fysetc #elif MB(FYSETC_CHEETAH_V12) - #include "stm32/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc + #include "stm32f1/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc #elif MB(LONGER3D_LK) - #include "stm32/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer + #include "stm32f1/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer #elif MB(MKS_ROBIN_LITE3) - #include "stm32/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 + #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 #elif MB(MKS_ROBIN_PRO) - #include "stm32/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro + #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro // // ARM Cortex-M4F @@ -529,46 +529,46 @@ // #elif MB(BEAST) - #include "stm32/pins_BEAST.h" // STM32F4 env:STM32F4 + #include "stm32f4/pins_BEAST.h" // STM32F4 env:STM32F4 #elif MB(GENERIC_STM32F4) - #include "stm32/pins_GENERIC_STM32F4.h" // STM32F4 env:STM32F4 + #include "stm32f4/pins_GENERIC_STM32F4.h" // STM32F4 env:STM32F4 #elif MB(ARMED) - #include "stm32/pins_ARMED.h" // STM32F4 env:ARMED + #include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED #elif MB(RUMBA32_AUS3D) - #include "stm32/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32_f446ve + #include "stm32f4/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32_f446ve #elif MB(RUMBA32_MKS) - #include "stm32/pins_RUMBA32_MKS.h" // STM32F4 env:rumba32_mks + #include "stm32f4/pins_RUMBA32_MKS.h" // STM32F4 env:rumba32_mks #elif MB(BLACK_STM32F407VE) - #include "stm32/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black + #include "stm32f4/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black #elif MB(STEVAL_3DP001V1) - #include "stm32/pins_STEVAL_3DP001V1.h" // STM32F4 env:STM32F401VE_STEVAL + #include "stm32f4/pins_STEVAL_3DP001V1.h" // STM32F4 env:STM32F401VE_STEVAL #elif MB(BTT_SKR_PRO_V1_1) - #include "stm32/pins_BTT_SKR_PRO_V1_1.h" // STM32F4 env:BIGTREE_SKR_PRO + #include "stm32f4/pins_BTT_SKR_PRO_V1_1.h" // STM32F4 env:BIGTREE_SKR_PRO #elif MB(BTT_GTR_V1_0) - #include "stm32/pins_BTT_GTR_V1_0.h" // STM32F4 env:BIGTREE_GTR_V1_0 + #include "stm32f4/pins_BTT_GTR_V1_0.h" // STM32F4 env:BIGTREE_GTR_V1_0 #elif MB(BTT_BTT002_V1_0) - #include "stm32/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 + #include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 #elif MB(LERDGE_K) - #include "stm32/pins_LERDGE_K.h" // STM32F4 env:STM32F4 + #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:STM32F4 #elif MB(LERDGE_X) - #include "stm32/pins_LERDGE_X.h" // STM32F4 env:STM32F4 + #include "stm32f4/pins_LERDGE_X.h" // STM32F4 env:STM32F4 #elif MB(VAKE403D) - #include "stm32/pins_VAKE403D.h" // STM32F4 env:STM32F4 + #include "stm32f4/pins_VAKE403D.h" // STM32F4 env:STM32F4 #elif MB(FYSETC_S6) - #include "stm32/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 + #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 #elif MB(FLYF407ZG) - #include "stm32/pins_FLYF407ZG.h" // STM32F4 env:FLYF407ZG + #include "stm32f4/pins_FLYF407ZG.h" // STM32F4 env:FLYF407ZG #elif MB(MKS_ROBIN2) - #include "pins_MKS_ROBIN2.h" // STM32F4 env:MKS_ROBIN2 + #include "stm32f4/pins_MKS_ROBIN2.h" // STM32F4 env:MKS_ROBIN2 // // ARM Cortex M7 // #elif MB(THE_BORG) - #include "stm32/pins_THE_BORG.h" // STM32F7 env:STM32F7 + #include "stm32f7/pins_THE_BORG.h" // STM32F7 env:STM32F7 #elif MB(REMRAM_V1) - #include "stm32/pins_REMRAM_V1.h" // STM32F7 env:STM32F7 + #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:STM32F7 // // Espressif ESP32 diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_SKR_E3_DIP.h rename to Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3.h rename to Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_0.h rename to Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_SKR_MINI_E3_V1_2.h rename to Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_SKR_MINI_V1_1.h rename to Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h diff --git a/Marlin/src/pins/stm32/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h similarity index 100% rename from Marlin/src/pins/stm32/pins_CHITU3D.h rename to Marlin/src/pins/stm32f1/pins_CHITU3D.h diff --git a/Marlin/src/pins/stm32/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h similarity index 100% rename from Marlin/src/pins/stm32/pins_FYSETC_AIO_II.h rename to Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h diff --git a/Marlin/src/pins/stm32/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h similarity index 100% rename from Marlin/src/pins/stm32/pins_FYSETC_CHEETAH.h rename to Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h diff --git a/Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h similarity index 100% rename from Marlin/src/pins/stm32/pins_FYSETC_CHEETAH_V12.h rename to Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h diff --git a/Marlin/src/pins/stm32/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h similarity index 100% rename from Marlin/src/pins/stm32/pins_GTM32_MINI.h rename to Marlin/src/pins/stm32f1/pins_GTM32_MINI.h diff --git a/Marlin/src/pins/stm32/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h similarity index 100% rename from Marlin/src/pins/stm32/pins_GTM32_MINI_A30.h rename to Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h diff --git a/Marlin/src/pins/stm32/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h similarity index 100% rename from Marlin/src/pins/stm32/pins_GTM32_PRO_VB.h rename to Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h diff --git a/Marlin/src/pins/stm32/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h similarity index 100% rename from Marlin/src/pins/stm32/pins_GTM32_REV_B.h rename to Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h diff --git a/Marlin/src/pins/stm32/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h similarity index 100% rename from Marlin/src/pins/stm32/pins_JGAURORA_A5S_A1.h rename to Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h diff --git a/Marlin/src/pins/stm32/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h similarity index 100% rename from Marlin/src/pins/stm32/pins_LONGER3D_LK.h rename to Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h diff --git a/Marlin/src/pins/stm32/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MALYAN_M200.h rename to Marlin/src/pins/stm32f1/pins_MALYAN_M200.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN.h rename to Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN_LITE.h rename to Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN_LITE3.h rename to Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN_MINI.h rename to Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN_NANO.h rename to Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN_PRO.h rename to Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h diff --git a/Marlin/src/pins/stm32/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MORPHEUS.h rename to Marlin/src/pins/stm32f1/pins_MORPHEUS.h diff --git a/Marlin/src/pins/stm32/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h similarity index 100% rename from Marlin/src/pins/stm32/pins_STM32F1R.h rename to Marlin/src/pins/stm32f1/pins_STM32F1R.h diff --git a/Marlin/src/pins/stm32/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h similarity index 100% rename from Marlin/src/pins/stm32/pins_STM3R_MINI.h rename to Marlin/src/pins/stm32f1/pins_STM3R_MINI.h diff --git a/Marlin/src/pins/stm32/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h similarity index 100% rename from Marlin/src/pins/stm32/pins_ARMED.h rename to Marlin/src/pins/stm32f4/pins_ARMED.h diff --git a/Marlin/src/pins/stm32/pins_BEAST.h b/Marlin/src/pins/stm32f4/pins_BEAST.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BEAST.h rename to Marlin/src/pins/stm32f4/pins_BEAST.h diff --git a/Marlin/src/pins/stm32/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BLACK_STM32F407VE.h rename to Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h diff --git a/Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_BTT002_V1_0.h rename to Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h diff --git a/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h rename to Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h similarity index 100% rename from Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h rename to Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h diff --git a/Marlin/src/pins/stm32/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h similarity index 100% rename from Marlin/src/pins/stm32/pins_FLYF407ZG.h rename to Marlin/src/pins/stm32f4/pins_FLYF407ZG.h diff --git a/Marlin/src/pins/stm32/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h similarity index 100% rename from Marlin/src/pins/stm32/pins_FYSETC_S6.h rename to Marlin/src/pins/stm32f4/pins_FYSETC_S6.h diff --git a/Marlin/src/pins/stm32/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h similarity index 100% rename from Marlin/src/pins/stm32/pins_GENERIC_STM32F4.h rename to Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h diff --git a/Marlin/src/pins/stm32/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h similarity index 100% rename from Marlin/src/pins/stm32/pins_LERDGE_K.h rename to Marlin/src/pins/stm32f4/pins_LERDGE_K.h diff --git a/Marlin/src/pins/stm32/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h similarity index 100% rename from Marlin/src/pins/stm32/pins_LERDGE_X.h rename to Marlin/src/pins/stm32f4/pins_LERDGE_X.h diff --git a/Marlin/src/pins/stm32/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h similarity index 100% rename from Marlin/src/pins/stm32/pins_MKS_ROBIN2.h rename to Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h diff --git a/Marlin/src/pins/stm32/pins_RUMBA32_AUS3D.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h similarity index 100% rename from Marlin/src/pins/stm32/pins_RUMBA32_AUS3D.h rename to Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h diff --git a/Marlin/src/pins/stm32/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h similarity index 100% rename from Marlin/src/pins/stm32/pins_RUMBA32_MKS.h rename to Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h diff --git a/Marlin/src/pins/stm32/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h similarity index 100% rename from Marlin/src/pins/stm32/pins_RUMBA32_common.h rename to Marlin/src/pins/stm32f4/pins_RUMBA32_common.h diff --git a/Marlin/src/pins/stm32/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h similarity index 100% rename from Marlin/src/pins/stm32/pins_STEVAL_3DP001V1.h rename to Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h diff --git a/Marlin/src/pins/stm32/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h similarity index 100% rename from Marlin/src/pins/stm32/pins_VAKE403D.h rename to Marlin/src/pins/stm32f4/pins_VAKE403D.h diff --git a/Marlin/src/pins/stm32/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h similarity index 100% rename from Marlin/src/pins/stm32/pins_REMRAM_V1.h rename to Marlin/src/pins/stm32f7/pins_REMRAM_V1.h diff --git a/Marlin/src/pins/stm32/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h similarity index 100% rename from Marlin/src/pins/stm32/pins_THE_BORG.h rename to Marlin/src/pins/stm32f7/pins_THE_BORG.h From 29874b21b6ef17bccd6db04e31c84aff79ed94d0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 22 Mar 2020 00:03:15 +0000 Subject: [PATCH 0017/1454] [cron] Bump distribution date (2020-03-22) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e6d77e842c..2f99b9a6ed 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-21" + #define STRING_DISTRIBUTION_DATE "2020-03-22" #endif /** From 1674df00b14009e7c3c2daa5c8585cabe3fc7fc4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 18:15:37 -0500 Subject: [PATCH 0018/1454] Stay at v0.91 of USBComposite for STM32F1 --- platformio.ini | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/platformio.ini b/platformio.ini index 39885b0cd3..62582e1d93 100644 --- a/platformio.ini +++ b/platformio.ini @@ -301,6 +301,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + USBComposite_stm32f1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -315,6 +316,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + USBComposite_stm32f1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -330,6 +332,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + USBComposite_stm32f1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -345,6 +348,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + USBComposite_stm32f1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 From 7988e31f5ecd5d6e67b6290db9079cf2c097c56f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 21:16:08 -0500 Subject: [PATCH 0019/1454] whitespace --- Marlin/src/gcode/config/M220.cpp | 2 +- Marlin/src/lcd/language/language_tr.h | 1 - buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/config/M220.cpp b/Marlin/src/gcode/config/M220.cpp index 5ea75c09c6..f24c11e23d 100644 --- a/Marlin/src/gcode/config/M220.cpp +++ b/Marlin/src/gcode/config/M220.cpp @@ -30,7 +30,7 @@ * S : Set the feed rate percentage factor * * Report the current speed percentage factor if no parameter is specified - * + * * With PRUSA_MMU2... * B : Flag to back up the current factor * R : Flag to restore the last-saved factor diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 0edade0374..096fef254c 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -606,4 +606,3 @@ namespace Language_tr { #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED_N #endif - diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h index ffdb81a636..571f3207e9 100644 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h +++ b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h @@ -195,7 +195,7 @@ extern "C" { #define PIN_SERIAL2_RX PD6 #define PIN_SERIAL2_TX PD5 #else - #error'Invalid setting for SERIAL_UART_INSTANCE' + #error "Invalid setting for SERIAL_UART_INSTANCE." #endif // Timer Definitions From e62b52da99883202f58aef71348823becfd61984 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 20:26:00 -0500 Subject: [PATCH 0020/1454] Use pin/port names for CHITU pins --- Marlin/src/pins/stm32f1/pins_CHITU3D.h | 152 ++++++++++++------------- 1 file changed, 76 insertions(+), 76 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index 2411500fb2..2db6b1bc0b 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -86,7 +86,7 @@ // #define SDSS -1 #define LED_PIN -1 -#define CASE_LIGHT_PIN 8 +#define CASE_LIGHT_PIN PA8 // 8 #define PS_ON_PIN -1 #define KILL_PIN PD6 // LED strip 24v @@ -111,8 +111,8 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA0 // Analog Input -#define TEMP_0_PIN PA1 // Analog Input +#define TEMP_BED_PIN PA0 // Analog Input +#define TEMP_0_PIN PA1 // Analog Input #define TEMP_1_PIN -1 // Analog Input #define TEMP_2_PIN -1 // Analog Input @@ -122,9 +122,9 @@ #if HAS_SPI_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PD3 // 51 // SID (MOSI) + #define LCD_PINS_D4 PD4 // 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) #define LCD_PINS_RS PB8 #define LCD_PINS_ENABLE PD2 @@ -140,13 +140,13 @@ #define LCD_PINS_D6 PB14 #define LCD_PINS_D7 PB15 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN PC1 // 33 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK PC6 // 38 + //#define SHIFT_LD PC10 // 42 + //#define SHIFT_OUT PC8 // 40 + //#define SHIFT_EN PA1 // 17 #endif #endif @@ -154,125 +154,125 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN PC5 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 PB15 // 31 + #define BTN_EN2 PC1 // 33 + #define BTN_ENC PC3 // 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN PD1 // 49 + #define KILL_PIN PC9 // 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 + #define LCD_BACKLIGHT_PIN PC7 // 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 PE0 // 64 + #define BTN_EN2 PD11 // 59 + #define BTN_ENC PD15 // 63 + #define SD_DETECT_PIN PC10 // 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 + #define BTN_EN1 PC15 // 47 + #define BTN_EN2 PC11 // 43 + #define BTN_ENC PC0 // 32 + #define LCD_SDSS PD5 // 53 #define SD_DETECT_PIN -1 - #define KILL_PIN 41 + #define KILL_PIN PC9 // 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 PB6 // 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 PA7 // 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define LCD_SDSS PD5 // 53 + #define SD_DETECT_PIN PD1 // 49 #elif ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 33 + #define BEEPER_PIN PC1 // 33 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 + #define DOGLCD_A0 PC12 // 44 + #define DOGLCD_CS PC13 // 45 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 PB6 // 22 + #define BTN_EN2 PA7 // 7 + #define BTN_ENC PC7 // 39 - #define SDSS 53 + #define SDSS PD5 // 53 #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 31 + #define KILL_PIN PB15 // 31 - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define STAT_LED_RED_PIN PC0 // 32 + #define STAT_LED_BLUE_PIN PC3 // 35 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 - #define LCD_BACKLIGHT_PIN 33 + #define BTN_EN1 PC3 // 35 + #define BTN_EN2 PC5 // 37 + #define BTN_ENC PB15 // 31 + #define SD_DETECT_PIN PD1 // 49 + #define LCD_SDSS PD5 // 53 + #define KILL_PIN PC9 // 41 + #define BEEPER_PIN PB7 // 23 + #define DOGLCD_CS PB13 // 29 + #define DOGLCD_A0 PB11 // 27 + #define LCD_BACKLIGHT_PIN PC1 // 33 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN PC10 // 42 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 + #define DOGLCD_A0 PC12 // 44 + #define DOGLCD_CS PE2 // 66 + #define LCD_BACKLIGHT_PIN PE1 // 65 // backlight LED on A11/D65 + #define SDSS PD5 // 53 - #define KILL_PIN 64 + #define KILL_PIN PE0 // 64 // GLCD features // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 PC8 // 40 + #define BTN_EN2 PD15 // 63 + #define BTN_ENC PD11 // 59 // not connected to a pin - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN PD1 // 49 #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN PC1 // 33 // Buttons directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #define BTN_EN1 PE0 // 64 + #define BTN_EN2 PD11 // 59 + #define BTN_ENC PD15 // 63 + #define SHIFT_OUT PC8 // 40 + #define SHIFT_CLK PC12 // 44 + #define SHIFT_LD PC10 // 42 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 PD11 // 59 // AUX2 PIN 3 + #define BTN_EN2 PD15 // 63 // AUX2 PIN 4 + #define BTN_ENC PD1 // 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 PC5 // 37 + #define BTN_EN2 PC3 // 35 + #define BTN_ENC PB15 // 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN PD1 // 49 + #define KILL_PIN PC9 // 41 #else //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif From 9340a339807da41a6b7c91325e2874d193d0a370 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 20:35:45 -0500 Subject: [PATCH 0021/1454] Add a pins formatting script --- buildroot/share/scripts/pinsformat.js | 141 ++++++++++++++++++++++++++ 1 file changed, 141 insertions(+) create mode 100755 buildroot/share/scripts/pinsformat.js diff --git a/buildroot/share/scripts/pinsformat.js b/buildroot/share/scripts/pinsformat.js new file mode 100755 index 0000000000..3e2a57b556 --- /dev/null +++ b/buildroot/share/scripts/pinsformat.js @@ -0,0 +1,141 @@ +#!/usr/bin/env node + +// +// Formatter script for pins_MYPINS.h files +// +// Usage: mffmt [infile] [outfile] +// +// With no parameters convert STDIN to STDOUT +// + +const fs = require("fs"); + +// String lpad / rpad +String.prototype.lpad = function(len, chr) { + if (!len) return this; + if (chr === undefined) chr = ' '; + var s = this+'', need = len - s.length; + if (need > 0) s = new Array(need+1).join(chr) + s; + return s; +}; + +String.prototype.rpad = function(len, chr) { + if (!len) return this; + if (chr === undefined) chr = ' '; + var s = this+'', need = len - s.length; + if (need > 0) s += new Array(need+1).join(chr); + return s; +}; + +const mpatt = [ '-?\\d+', 'P[A-I]\\d+', 'P\\d_\\d+' ], + definePatt = new RegExp(`^\\s*(//)?#define\\s+[A-Z_][A-Z0-9_]+\\s+(${mpatt[0]}|${mpatt[1]}|${mpatt[2]})\\s*(//.*)?$`, 'gm'), + ppad = [ 3, 4, 5 ], + col_comment = 50, + col_value_rj = col_comment - 3; + +var mexpr = []; +for (let m of mpatt) mexpr.push(new RegExp('^' + m + '$')); + +const argv = process.argv.slice(2), argc = argv.length; + +var src_file = 0, src_name = 'STDIN', dst_file; +if (argc > 0) { + src_file = src_name = argv[0]; + dst_file = argv[argc > 1 ? 1 : 0]; +} + +// Read from file or STDIN until it terminates +const filtered = process_text(fs.readFileSync(src_file).toString()); +if (dst_file) + fs.writeFileSync(dst_file, filtered); +else + console.log(filtered); + +// Find the pin pattern so non-pin defines can be skipped +function get_pin_pattern(txt) { + var r, m = 0, match_count = [ 0, 0, 0 ]; + definePatt.lastIndex = 0; + while ((r = definePatt.exec(txt)) !== null) { + let ind = -1; + if (mexpr.some((p) => { + ind++; + const didmatch = r[2].match(p); + return r[2].match(p); + }) ) { + const m = ++match_count[ind]; + if (m >= 10) { + return { match: mpatt[ind], pad:ppad[ind] }; + } + } + } + return null; +} + +function process_text(txt) { + if (!txt.length) return '(no text)'; + const patt = get_pin_pattern(txt); + if (!patt) return txt; + const pindefPatt = new RegExp(`^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+(${patt.match})\\s*(//.*)?$`), + noPinPatt = new RegExp(`^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+(-1)\\s*(//.*)?$`), + skipPatt = new RegExp('^(\\s*(//)?#define)\\s+(AT90USB|USBCON|BOARD_.+|.+_MACHINE_NAME|.+_SERIAL)\\s+(.+)\\s*(//.*)?$'), + aliasPatt = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+([A-Z_][A-Z0-9_()]+)\\s*(//.*)?$'), + switchPatt = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s*(//.*)?$'), + undefPatt = new RegExp('^(\\s*(//)?#undef)\\s+([A-Z_][A-Z0-9_]+)\\s*(//.*)?$'), + defPatt = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+(\\w+)\\s*(//.*)?$'), + condPatt = new RegExp('^(\\s*(//)?#(if|ifn?def|else|elif)(\\s+\\S+)*)\\s+(//.*)$'), + commPatt = new RegExp('^\\s{20,}(//.*)?$'); + const col_value_lj = col_comment - patt.pad - 2; + var r, out = '', check_comment_next = false; + txt.split('\n').forEach((line) => { + if (check_comment_next) + check_comment_next = ((r = commPatt.exec(line)) !== null); + + if (check_comment_next) + // Comments in column 45 + line = ''.rpad(col_comment) + r[1]; + + else if ((r = pindefPatt.exec(line)) !== null) { + // + // #define MY_PIN [pin] + // + const pinnum = r[4].charAt(0) == 'P' ? r[4] : r[4].lpad(patt.pad); + line = r[1] + ' ' + r[3]; + line = line.rpad(col_value_lj) + pinnum; + if (r[5]) line = line.rpad(col_comment) + r[5]; + } + else if ((r = noPinPatt.exec(line)) !== null) { + // + // #define MY_PIN -1 + // + line = r[1] + ' ' + r[3]; + line = line.rpad(col_value_lj) + '-1'; + if (r[5]) line = line.rpad(col_comment) + r[5]; + } + else if ((r = skipPatt.exec(line)) !== null) { + } + else if ((r = aliasPatt.exec(line)) !== null) { + line = r[1] + ' ' + r[3]; + line += r[4].lpad(col_value_rj + 1 - line.length); + if (r[5]) line = line.rpad(col_comment) + r[5]; + } + else if ((r = switchPatt.exec(line)) !== null) { + line = r[1] + ' ' + r[3]; + if (r[4]) line = line.rpad(col_comment) + r[4]; + check_comment_next = true; + } + else if ((r = defPatt.exec(line)) !== null) { + line = r[1] + ' ' + r[3] + ' ' + r[4]; + if (r[5]) line = line.rpad(col_comment) + r[5]; + } + else if ((r = undefPatt.exec(line)) !== null) { + line = r[1] + ' ' + r[3]; + if (r[4]) line = line.rpad(col_comment) + r[4]; + } + else if ((r = condPatt.exec(line)) !== null) { + line = r[1].rpad(col_comment) + r[5]; + check_comment_next = true; + } + out += line + '\n'; + }); + return out.replace(/\n\n+/g, '\n\n').replace(/\n\n$/g, '\n'); +} From 2c325c2a7d9b66b50d8585a1d5ced422ed88b1ae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 21:13:19 -0500 Subject: [PATCH 0022/1454] Format some pins files --- Marlin/src/pins/esp32/pins_E4D.h | 56 +-- Marlin/src/pins/esp32/pins_ESP32.h | 56 +-- Marlin/src/pins/esp32/pins_MRR_ESPA.h | 68 +-- Marlin/src/pins/esp32/pins_MRR_ESPE.h | 122 ++--- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 454 ++++++++--------- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 110 ++-- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 90 ++-- Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h | 81 ++- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 137 +++-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 242 ++++----- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 206 ++++---- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 44 +- Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 132 ++--- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 234 ++++----- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 242 ++++----- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 316 ++++++------ Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h | 87 ++-- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h | 91 ++-- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h | 146 +++--- .../src/pins/lpc1769/pins_COHESION3D_MINI.h | 116 ++--- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 196 ++++---- Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 20 +- Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h | 82 +-- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 114 ++--- Marlin/src/pins/mega/pins_CHEAPTRONIC.h | 48 +- Marlin/src/pins/mega/pins_CHEAPTRONICv2.h | 112 ++--- Marlin/src/pins/mega/pins_CNCONTROLS_11.h | 132 ++--- Marlin/src/pins/mega/pins_CNCONTROLS_12.h | 138 ++--- Marlin/src/pins/mega/pins_CNCONTROLS_15.h | 78 +-- Marlin/src/pins/mega/pins_EINSTART-S.h | 68 +-- Marlin/src/pins/mega/pins_ELEFU_3.h | 104 ++-- Marlin/src/pins/mega/pins_GT2560_REV_A.h | 120 ++--- Marlin/src/pins/mega/pins_GT2560_V3.h | 114 ++--- Marlin/src/pins/mega/pins_GT2560_V3_A20.h | 14 +- Marlin/src/pins/mega/pins_GT2560_V3_MC2.h | 8 +- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 124 ++--- Marlin/src/pins/mega/pins_LEAPFROG.h | 66 +-- Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h | 72 +-- Marlin/src/pins/mega/pins_MEGACONTROLLER.h | 110 ++-- Marlin/src/pins/mega/pins_MEGATRONICS.h | 96 ++-- Marlin/src/pins/mega/pins_MEGATRONICS_2.h | 114 ++--- Marlin/src/pins/mega/pins_MEGATRONICS_3.h | 164 +++--- Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 204 ++++---- Marlin/src/pins/mega/pins_MINITRONICS.h | 108 ++-- Marlin/src/pins/mega/pins_OVERLORD.h | 100 ++-- Marlin/src/pins/mega/pins_PICA.h | 96 ++-- Marlin/src/pins/mega/pins_PICAOLD.h | 8 +- Marlin/src/pins/mega/pins_SILVER_GATE.h | 84 ++-- Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h | 70 +-- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 124 ++--- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 142 +++--- Marlin/src/pins/rambo/pins_MINIRAMBO.h | 146 +++--- Marlin/src/pins/rambo/pins_RAMBO.h | 188 +++---- Marlin/src/pins/rambo/pins_SCOOVO_X9H.h | 140 +++--- Marlin/src/pins/ramps/pins_3DRAG.h | 56 +-- Marlin/src/pins/ramps/pins_AZTEEG_X3.h | 32 +- Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h | 94 ++-- Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h | 10 +- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 47 +- .../src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h | 70 +-- Marlin/src/pins/ramps/pins_FELIX2.h | 10 +- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h | 124 ++--- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h | 28 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 126 ++--- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 132 +++-- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 184 +++---- Marlin/src/pins/ramps/pins_FYSETC_F6_14.h | 26 +- Marlin/src/pins/ramps/pins_K8400.h | 10 +- Marlin/src/pins/ramps/pins_K8800.h | 80 +-- Marlin/src/pins/ramps/pins_MKS_BASE_14.h | 20 +- Marlin/src/pins/ramps/pins_MKS_BASE_16.h | 14 +- Marlin/src/pins/ramps/pins_MKS_BASE_common.h | 36 +- Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 28 +- Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h | 32 +- Marlin/src/pins/ramps/pins_RAMPS.h | 476 +++++++++--------- Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h | 26 +- Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h | 10 +- Marlin/src/pins/ramps/pins_RAMPS_OLD.h | 74 +-- Marlin/src/pins/ramps/pins_RAMPS_PLUS.h | 22 +- Marlin/src/pins/ramps/pins_RIGIDBOARD.h | 60 +-- Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h | 12 +- Marlin/src/pins/ramps/pins_RL200.h | 18 +- Marlin/src/pins/ramps/pins_RUMBA.h | 158 +++--- Marlin/src/pins/ramps/pins_TANGO.h | 14 +- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 62 +-- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 436 ++++++++-------- Marlin/src/pins/ramps/pins_ULTIMAIN_2.h | 100 ++-- Marlin/src/pins/ramps/pins_ULTIMAKER.h | 122 ++--- Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h | 170 +++---- Marlin/src/pins/ramps/pins_VORON.h | 10 +- Marlin/src/pins/ramps/pins_ZRIB_V20.h | 46 +- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 188 +++---- Marlin/src/pins/sam/pins_ADSK.h | 62 +-- Marlin/src/pins/sam/pins_ALLIGATOR_R2.h | 136 ++--- Marlin/src/pins/sam/pins_ARCHIM1.h | 158 +++--- Marlin/src/pins/sam/pins_ARCHIM2.h | 186 +++---- Marlin/src/pins/sam/pins_CNCONTROLS_15D.h | 92 ++-- Marlin/src/pins/sam/pins_DUE3DOM.h | 148 +++--- Marlin/src/pins/sam/pins_DUE3DOM_MINI.h | 152 +++--- Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h | 116 ++--- Marlin/src/pins/sam/pins_RADDS.h | 232 ++++----- Marlin/src/pins/sam/pins_RAMPS_DUO.h | 34 +- Marlin/src/pins/sam/pins_RAMPS_FD_V1.h | 164 +++--- Marlin/src/pins/sam/pins_RAMPS_SMART.h | 28 +- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 202 ++++---- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 190 +++---- Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h | 142 +++--- Marlin/src/pins/samd/pins_RAMPS_144.h | 218 ++++---- Marlin/src/pins/sanguino/pins_ANET_10.h | 84 ++-- .../src/pins/sanguino/pins_GEN3_MONOLITHIC.h | 38 +- Marlin/src/pins/sanguino/pins_GEN3_PLUS.h | 43 +- Marlin/src/pins/sanguino/pins_GEN6.h | 54 +- Marlin/src/pins/sanguino/pins_GEN7_12.h | 79 ++- Marlin/src/pins/sanguino/pins_GEN7_14.h | 56 +-- Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h | 76 +-- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 14 +- Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h | 12 +- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 20 +- Marlin/src/pins/sanguino/pins_OMCA.h | 70 +-- Marlin/src/pins/sanguino/pins_OMCA_A.h | 50 +- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 190 +++---- Marlin/src/pins/sanguino/pins_SETHI.h | 56 +-- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 126 ++--- .../src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 118 ++--- .../pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h | 18 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 130 ++--- Marlin/src/pins/stm32f1/pins_CHITU3D.h | 270 +++++----- Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h | 92 ++-- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 76 +-- .../pins/stm32f1/pins_FYSETC_CHEETAH_V12.h | 18 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 130 ++--- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 130 ++--- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 130 ++--- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 136 ++--- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 82 +-- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 114 ++--- Marlin/src/pins/stm32f1/pins_MALYAN_M200.h | 46 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 124 ++--- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 94 ++-- .../src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h | 106 ++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 90 ++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 86 ++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 198 ++++---- Marlin/src/pins/stm32f1/pins_MORPHEUS.h | 46 +- Marlin/src/pins/stm32f1/pins_STM32F1R.h | 222 ++++---- Marlin/src/pins/stm32f1/pins_STM3R_MINI.h | 244 ++++----- Marlin/src/pins/stm32f4/pins_ARMED.h | 188 +++---- Marlin/src/pins/stm32f4/pins_BEAST.h | 252 +++++----- .../src/pins/stm32f4/pins_BLACK_STM32F407VE.h | 128 ++--- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 138 ++--- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 314 ++++++------ .../src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 186 ++++--- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 237 +++++---- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 194 +++---- .../src/pins/stm32f4/pins_GENERIC_STM32F4.h | 121 +++-- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 112 ++--- Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 108 ++-- Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h | 69 ++- Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h | 30 +- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 126 ++--- .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 210 ++++---- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 146 +++--- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 106 ++-- Marlin/src/pins/stm32f7/pins_THE_BORG.h | 168 +++---- Marlin/src/pins/teensy2/pins_5DPRINT.h | 68 +-- Marlin/src/pins/teensy2/pins_BRAINWAVE.h | 50 +- Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h | 50 +- Marlin/src/pins/teensy2/pins_PRINTRBOARD.h | 92 ++-- .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 156 +++--- Marlin/src/pins/teensy2/pins_SAV_MKI.h | 108 ++-- Marlin/src/pins/teensy2/pins_TEENSY2.h | 72 +-- Marlin/src/pins/teensy2/pins_TEENSYLU.h | 73 ++- Marlin/src/pins/teensy3/pins_TEENSY31_32.h | 82 +-- Marlin/src/pins/teensy3/pins_TEENSY35_36.h | 94 ++-- 174 files changed, 9635 insertions(+), 9668 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index 409f381297..829c391c4d 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -42,49 +42,49 @@ // // Limit Switches // -#define X_MIN_PIN 34 -#define Y_MIN_PIN 35 -#define Z_MIN_PIN 16 // 15 +#define X_MIN_PIN 34 +#define Y_MIN_PIN 35 +#define Z_MIN_PIN 16 // 15 // // Steppers // -#define X_STEP_PIN 12 // 34//27 -#define X_DIR_PIN 13 // 35//26 -#define X_ENABLE_PIN 17 // 0//17//25 // used free pin -//#define X_CS_PIN 0 +#define X_STEP_PIN 12 // 34//27 +#define X_DIR_PIN 13 // 35//26 +#define X_ENABLE_PIN 17 // 0//17//25 // used free pin +//#define X_CS_PIN 0 -#define Y_STEP_PIN 32 // 33 -#define Y_DIR_PIN 33 // 32 -#define Y_ENABLE_PIN X_ENABLE_PIN -//#define Y_CS_PIN 13 +#define Y_STEP_PIN 32 // 33 +#define Y_DIR_PIN 33 // 32 +#define Y_ENABLE_PIN X_ENABLE_PIN +//#define Y_CS_PIN 13 -#define Z_STEP_PIN 25 // 14 -#define Z_DIR_PIN 26 // 12 -#define Z_ENABLE_PIN X_ENABLE_PIN -//#define Z_CS_PIN 5 // SS_PIN +#define Z_STEP_PIN 25 // 14 +#define Z_DIR_PIN 26 // 12 +#define Z_ENABLE_PIN X_ENABLE_PIN +//#define Z_CS_PIN 5 // SS_PIN -#define E0_STEP_PIN 27 // 16 -#define E0_DIR_PIN 14 // 17 -#define E0_ENABLE_PIN X_ENABLE_PIN -//#define E0_CS_PIN 21 +#define E0_STEP_PIN 27 // 16 +#define E0_DIR_PIN 14 // 17 +#define E0_ENABLE_PIN X_ENABLE_PIN +//#define E0_CS_PIN 21 // // Temperature Sensors // -#define TEMP_0_PIN 36 // Analog Input -#define TEMP_BED_PIN 39 // Analog Input +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_BED_PIN 39 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 // 4//2//(D8) -#define FAN_PIN 0 // 2//15//13 (D9) -#define HEATER_BED_PIN 15 // 15//0 //(D10) +#define HEATER_0_PIN 2 // 4//2//(D8) +#define FAN_PIN 0 // 2//15//13 (D9) +#define HEATER_BED_PIN 15 // 15//0 //(D10) // SPI -#define SDSS 5 +#define SDSS 5 #define I2S_STEPPER_STREAM -#define I2S_WS 23 -#define I2S_BCK 22 -#define I2S_DATA 21 +#define I2S_WS 23 +#define I2S_BCK 22 +#define I2S_DATA 21 diff --git a/Marlin/src/pins/esp32/pins_ESP32.h b/Marlin/src/pins/esp32/pins_ESP32.h index 99a5ea2f76..e4da400528 100644 --- a/Marlin/src/pins/esp32/pins_ESP32.h +++ b/Marlin/src/pins/esp32/pins_ESP32.h @@ -35,52 +35,52 @@ // I2S (steppers & other output-only pins) // #define I2S_STEPPER_STREAM -#define I2S_WS 25 -#define I2S_BCK 26 -#define I2S_DATA 27 +#define I2S_WS 25 +#define I2S_BCK 26 +#define I2S_DATA 27 // // Limit Switches // -#define X_MIN_PIN 34 -#define Y_MIN_PIN 35 -#define Z_MIN_PIN 15 +#define X_MIN_PIN 34 +#define Y_MIN_PIN 35 +#define Z_MIN_PIN 15 // // Steppers // -#define X_STEP_PIN 128 -#define X_DIR_PIN 129 -#define X_ENABLE_PIN 130 -//#define X_CS_PIN 0 +#define X_STEP_PIN 128 +#define X_DIR_PIN 129 +#define X_ENABLE_PIN 130 +//#define X_CS_PIN 0 -#define Y_STEP_PIN 131 -#define Y_DIR_PIN 132 -#define Y_ENABLE_PIN 133 -//#define Y_CS_PIN 13 +#define Y_STEP_PIN 131 +#define Y_DIR_PIN 132 +#define Y_ENABLE_PIN 133 +//#define Y_CS_PIN 13 -#define Z_STEP_PIN 134 -#define Z_DIR_PIN 135 -#define Z_ENABLE_PIN 136 -//#define Z_CS_PIN 5 // SS_PIN +#define Z_STEP_PIN 134 +#define Z_DIR_PIN 135 +#define Z_ENABLE_PIN 136 +//#define Z_CS_PIN 5 // SS_PIN -#define E0_STEP_PIN 137 -#define E0_DIR_PIN 138 -#define E0_ENABLE_PIN 139 -//#define E0_CS_PIN 21 +#define E0_STEP_PIN 137 +#define E0_DIR_PIN 138 +#define E0_ENABLE_PIN 139 +//#define E0_CS_PIN 21 // // Temperature Sensors // -#define TEMP_0_PIN 36 // Analog Input -#define TEMP_BED_PIN 39 // Analog Input +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_BED_PIN 39 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define FAN_PIN 13 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define FAN_PIN 13 +#define HEATER_BED_PIN 4 // SPI -#define SDSS 5 +#define SDSS 5 diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index a93f0f05c4..8a06f9a169 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -45,66 +45,66 @@ #ifdef I2S_STEPPER_STREAM #undef I2S_STEPPER_STREAM #endif -#define I2S_WS -1 -#define I2S_BCK -1 -#define I2S_DATA -1 +#define I2S_WS -1 +#define I2S_BCK -1 +#define I2S_DATA -1 // // Limit Switches // -#define X_STOP_PIN 34 -#define Y_STOP_PIN 35 -#define Z_STOP_PIN 15 +#define X_STOP_PIN 34 +#define Y_STOP_PIN 35 +#define Z_STOP_PIN 15 // // Steppers // -#define X_STEP_PIN 27 -#define X_DIR_PIN 26 -#define X_ENABLE_PIN 25 -//#define X_CS_PIN 21 +#define X_STEP_PIN 27 +#define X_DIR_PIN 26 +#define X_ENABLE_PIN 25 +//#define X_CS_PIN 21 -#define Y_STEP_PIN 33 -#define Y_DIR_PIN 32 -#define Y_ENABLE_PIN X_ENABLE_PIN -//#define Y_CS_PIN 22 +#define Y_STEP_PIN 33 +#define Y_DIR_PIN 32 +#define Y_ENABLE_PIN X_ENABLE_PIN +//#define Y_CS_PIN 22 -#define Z_STEP_PIN 14 -#define Z_DIR_PIN 12 -#define Z_ENABLE_PIN X_ENABLE_PIN -//#define Z_CS_PIN 5 // SS_PIN +#define Z_STEP_PIN 14 +#define Z_DIR_PIN 12 +#define Z_ENABLE_PIN X_ENABLE_PIN +//#define Z_CS_PIN 5 // SS_PIN -#define E0_STEP_PIN 16 -#define E0_DIR_PIN 17 -#define E0_ENABLE_PIN X_ENABLE_PIN -//#define E0_CS_PIN 21 +#define E0_STEP_PIN 16 +#define E0_DIR_PIN 17 +#define E0_ENABLE_PIN X_ENABLE_PIN +//#define E0_CS_PIN 21 // // Temperature Sensors // -#define TEMP_0_PIN 36 // Analog Input -#define TEMP_BED_PIN 39 // Analog Input +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_BED_PIN 39 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define FAN_PIN 13 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define FAN_PIN 13 +#define HEATER_BED_PIN 4 // // MicroSD card // -#define MOSI_PIN 23 -#define MISO_PIN 19 -#define SCK_PIN 18 -#define SDSS 5 -#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers +#define MOSI_PIN 23 +#define MISO_PIN 19 +#define SCK_PIN 18 +#define SDSS 5 +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers // Hardware serial pins // Add the following to Configuration.h or Configuration_adv.h to assign // specific pins to hardware Serial1. // Note: Serial2 can be defined using HARDWARE_SERIAL2_RX and HARDWARE_SERIAL2_TX but // MRR ESPA does not have enough spare pins for such reassignment. -//#define HARDWARE_SERIAL1_RX 21 -//#define HARDWARE_SERIAL1_TX 22 +//#define HARDWARE_SERIAL1_RX 21 +//#define HARDWARE_SERIAL1_TX 22 diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index 0096027158..3dd50489df 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -43,9 +43,9 @@ // // Limit Switches // -#define X_STOP_PIN 35 -#define Y_STOP_PIN 32 -#define Z_STOP_PIN 33 +#define X_STOP_PIN 35 +#define Y_STOP_PIN 32 +#define Z_STOP_PIN 33 // // Enable I2S stepper stream @@ -53,72 +53,72 @@ #undef I2S_STEPPER_STREAM #define I2S_STEPPER_STREAM -#undef LIN_ADVANCE // Currently, I2S stream does not work with linear advance +#undef LIN_ADVANCE // Currently, I2S stream does not work with linear advance -#define I2S_WS 26 -#define I2S_BCK 25 -#define I2S_DATA 27 +#define I2S_WS 26 +#define I2S_BCK 25 +#define I2S_DATA 27 // // Steppers // -#define X_STEP_PIN 129 -#define X_DIR_PIN 130 -#define X_ENABLE_PIN 128 -//#define X_CS_PIN 21 +#define X_STEP_PIN 129 +#define X_DIR_PIN 130 +#define X_ENABLE_PIN 128 +//#define X_CS_PIN 21 -#define Y_STEP_PIN 132 -#define Y_DIR_PIN 133 -#define Y_ENABLE_PIN 131 -//#define Y_CS_PIN 22 +#define Y_STEP_PIN 132 +#define Y_DIR_PIN 133 +#define Y_ENABLE_PIN 131 +//#define Y_CS_PIN 22 -#define Z_STEP_PIN 135 -#define Z_DIR_PIN 136 -#define Z_ENABLE_PIN 134 -//#define Z_CS_PIN 5 // SS_PIN +#define Z_STEP_PIN 135 +#define Z_DIR_PIN 136 +#define Z_ENABLE_PIN 134 +//#define Z_CS_PIN 5 // SS_PIN -#define E0_STEP_PIN 138 -#define E0_DIR_PIN 139 -#define E0_ENABLE_PIN 137 -//#define E0_CS_PIN 21 +#define E0_STEP_PIN 138 +#define E0_DIR_PIN 139 +#define E0_ENABLE_PIN 137 +//#define E0_CS_PIN 21 -#define E1_STEP_PIN 141 -#define E1_DIR_PIN 142 -#define E1_ENABLE_PIN 140 -//#define E1_CS_PIN 22 +#define E1_STEP_PIN 141 +#define E1_DIR_PIN 142 +#define E1_ENABLE_PIN 140 +//#define E1_CS_PIN 22 -#define Z2_STEP_PIN 141 -#define Z2_DIR_PIN 142 -#define Z2_ENABLE_PIN 140 -//#define Z2_CS_PIN 5 +#define Z2_STEP_PIN 141 +#define Z2_DIR_PIN 142 +#define Z2_ENABLE_PIN 140 +//#define Z2_CS_PIN 5 // // Temperature Sensors // -#define TEMP_0_PIN 36 // Analog Input -#define TEMP_1_PIN 34 // Analog Input -#define TEMP_BED_PIN 39 // Analog Input +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_1_PIN 34 // Analog Input +#define TEMP_BED_PIN 39 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 145 // 2 -#define FAN_PIN 146 // 15 -#define HEATER_BED_PIN 144 // 4 +#define HEATER_0_PIN 145 // 2 +#define FAN_PIN 146 // 15 +#define HEATER_BED_PIN 144 // 4 -#define CONTROLLER_FAN_PIN 147 -//#define E0_AUTO_FAN_PIN 148 // need to update Configuration_adv.h @section extruder -//#define E1_AUTO_FAN_PIN 149 // need to update Configuration_adv.h @section extruder -#define FAN1_PIN 149 +#define CONTROLLER_FAN_PIN 147 +//#define E0_AUTO_FAN_PIN 148 // need to update Configuration_adv.h @section extruder +//#define E1_AUTO_FAN_PIN 149 // need to update Configuration_adv.h @section extruder +#define FAN1_PIN 149 // // MicroSD card // -#define MOSI_PIN 23 -#define MISO_PIN 19 -#define SCK_PIN 18 -#define SDSS 5 -#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers +#define MOSI_PIN 23 +#define MISO_PIN 19 +#define SCK_PIN 18 +#define SDSS 5 +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers ////////////////////////// // LCDs and Controllers // @@ -126,21 +126,21 @@ #if HAS_GRAPHICAL_LCD - #define LCD_PINS_RS 13 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 + #define LCD_PINS_RS 13 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 16 #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN 151 + #define BEEPER_PIN 151 #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BEEPER_PIN 151 + #define BEEPER_PIN 151 - //#define LCD_PINS_D5 150 - //#define LCD_PINS_D6 152 - //#define LCD_PINS_D7 153 + //#define LCD_PINS_D5 150 + //#define LCD_PINS_D6 152 + //#define LCD_PINS_D7 153 #else @@ -148,9 +148,9 @@ #endif - #define BTN_EN1 0 - #define BTN_EN2 12 - #define BTN_ENC 14 + #define BTN_EN1 0 + #define BTN_EN2 12 + #define BTN_ENC 14 #endif // HAS_GRAPHICAL_LCD @@ -159,7 +159,7 @@ // specific pins to hardware Serial1 and Serial2. // Note: Serial2 can be defined using HARDWARE_SERIAL2_RX and HARDWARE_SERIAL2_TX but // MRR ESPA does not have enough spare pins for such reassignment. -//#define HARDWARE_SERIAL1_RX 21 -//#define HARDWARE_SERIAL1_TX 22 -//#define HARDWARE_SERIAL2_RX 2 -//#define HARDWARE_SERIAL2_TX 4 +//#define HARDWARE_SERIAL1_RX 21 +//#define HARDWARE_SERIAL1_TX 22 +//#define HARDWARE_SERIAL2_RX 2 +//#define HARDWARE_SERIAL2_TX 4 diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index b1f7ecee38..0bfbaabdcd 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -49,7 +49,7 @@ #define BOARD_INFO_NAME "RAMPS 1.4" #endif -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB #define IS_RAMPS_EFB @@ -57,85 +57,85 @@ // Servos // #ifdef IS_RAMPS_13 - #define SERVO0_PIN 7 // RAMPS_13 // Will conflict with BTN_EN2 on LCD_I2C_VIKI + #define SERVO0_PIN 7 // RAMPS_13 // Will conflict with BTN_EN2 on LCD_I2C_VIKI #else - #define SERVO0_PIN 11 + #define SERVO0_PIN 11 #endif -#define SERVO1_PIN 6 -#define SERVO2_PIN 5 +#define SERVO1_PIN 6 +#define SERVO2_PIN 5 #ifndef SERVO3_PIN - #define SERVO3_PIN 4 + #define SERVO3_PIN 4 #endif // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN 3 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN 2 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN 53 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN 49 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN 40 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN 42 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN 44 #endif // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -159,72 +159,72 @@ // Heaters / Fans // #ifndef MOSFET_D_PIN - #define MOSFET_D_PIN -1 + #define MOSFET_D_PIN -1 #endif #ifndef RAMPS_D8_PIN - #define RAMPS_D8_PIN 8 + #define RAMPS_D8_PIN 8 #endif #ifndef RAMPS_D9_PIN - #define RAMPS_D9_PIN 9 + #define RAMPS_D9_PIN 9 #endif #ifndef RAMPS_D10_PIN - #define RAMPS_D10_PIN 10 + #define RAMPS_D10_PIN 10 #endif -#define HEATER_0_PIN RAMPS_D10_PIN +#define HEATER_0_PIN RAMPS_D10_PIN -#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed - #define FAN_PIN RAMPS_D9_PIN - #define HEATER_BED_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan - #define HEATER_1_PIN RAMPS_D9_PIN - #define FAN_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed - #define HEATER_1_PIN RAMPS_D9_PIN - #define HEATER_BED_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan - #define FAN_PIN RAMPS_D9_PIN - #define FAN1_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_SF) // Spindle, Fan - #define FAN_PIN RAMPS_D8_PIN -#else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN RAMPS_D9_PIN - #define HEATER_BED_PIN RAMPS_D8_PIN +#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed + #define FAN_PIN RAMPS_D9_PIN + #define HEATER_BED_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan + #define HEATER_1_PIN RAMPS_D9_PIN + #define FAN_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed + #define HEATER_1_PIN RAMPS_D9_PIN + #define HEATER_BED_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan + #define FAN_PIN RAMPS_D9_PIN + #define FAN1_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_SF) // Spindle, Fan + #define FAN_PIN RAMPS_D8_PIN +#else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") + #define FAN_PIN RAMPS_D9_PIN + #define HEATER_BED_PIN RAMPS_D8_PIN #if HOTENDS == 1 - #define FAN1_PIN MOSFET_D_PIN + #define FAN1_PIN MOSFET_D_PIN #else - #define HEATER_1_PIN MOSFET_D_PIN + #define HEATER_1_PIN MOSFET_D_PIN #endif #endif #ifndef FAN_PIN - #define FAN_PIN 4 // IO pin. Buffer needed + #define FAN_PIN 4 // IO pin. Buffer needed #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS 53 +#define LED_PIN 13 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif // define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 4 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) - #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM - #elif HAS_FREE_AUX2_PINS // try to use AUX 2 - #define CASE_LIGHT_PIN 44 // Hardware PWM + #if NUM_SERVOS <= 1 // Prefer the servo connector + #define CASE_LIGHT_PIN 6 // Hardware PWM + #elif HAS_FREE_AUX2_PINS // try to use AUX 2 + #define CASE_LIGHT_PIN 44 // Hardware PWM #endif #endif @@ -232,14 +232,14 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) - #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 - #elif HAS_FREE_AUX2_PINS // try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_DIR_PIN 5 + #elif HAS_FREE_AUX2_PINS // try to use AUX 2 + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_DIR_PIN 65 #endif #endif @@ -247,13 +247,13 @@ // Průša i3 MK2 Multiplexer Support // #ifndef E_MUX0_PIN - #define E_MUX0_PIN 40 // Z_CS_PIN + #define E_MUX0_PIN 40 // Z_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 42 // E0_CS_PIN + #define E_MUX1_PIN 42 // E0_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 44 // E1_CS_PIN + #define E_MUX2_PIN 44 // E1_CS_PIN #endif /** @@ -261,13 +261,13 @@ */ #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 + #define TMC_SW_MOSI 66 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 + #define TMC_SW_MISO 44 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 + #define TMC_SW_SCK 64 #endif #endif @@ -295,91 +295,91 @@ */ #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 40 + #define X_SERIAL_TX_PIN 40 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_RX_PIN 63 #endif #ifndef X2_SERIAL_TX_PIN - #define X2_SERIAL_TX_PIN -1 + #define X2_SERIAL_TX_PIN -1 #endif #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN -1 + #define X2_SERIAL_RX_PIN -1 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 59 + #define Y_SERIAL_TX_PIN 59 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 64 + #define Y_SERIAL_RX_PIN 64 #endif #ifndef Y2_SERIAL_TX_PIN - #define Y2_SERIAL_TX_PIN -1 + #define Y2_SERIAL_TX_PIN -1 #endif #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN -1 + #define Y2_SERIAL_RX_PIN -1 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 42 + #define Z_SERIAL_TX_PIN 42 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 65 + #define Z_SERIAL_RX_PIN 65 #endif #ifndef Z2_SERIAL_TX_PIN - #define Z2_SERIAL_TX_PIN -1 + #define Z2_SERIAL_TX_PIN -1 #endif #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN -1 + #define Z2_SERIAL_RX_PIN -1 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 44 + #define E0_SERIAL_TX_PIN 44 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 66 + #define E0_SERIAL_RX_PIN 66 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN -1 + #define E1_SERIAL_TX_PIN -1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 + #define E1_SERIAL_RX_PIN -1 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN -1 + #define E2_SERIAL_TX_PIN -1 #endif #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 + #define E2_SERIAL_RX_PIN -1 #endif #ifndef E3_SERIAL_TX_PIN - #define E3_SERIAL_TX_PIN -1 + #define E3_SERIAL_TX_PIN -1 #endif #ifndef E3_SERIAL_RX_PIN - #define E3_SERIAL_RX_PIN -1 + #define E3_SERIAL_RX_PIN -1 #endif #ifndef E4_SERIAL_TX_PIN - #define E4_SERIAL_TX_PIN -1 + #define E4_SERIAL_TX_PIN -1 #endif #ifndef E4_SERIAL_RX_PIN - #define E4_SERIAL_RX_PIN -1 + #define E4_SERIAL_RX_PIN -1 #endif #ifndef E5_SERIAL_TX_PIN - #define E5_SERIAL_TX_PIN -1 + #define E5_SERIAL_TX_PIN -1 #endif #ifndef E5_SERIAL_RX_PIN - #define E5_SERIAL_RX_PIN -1 + #define E5_SERIAL_RX_PIN -1 #endif #ifndef E6_SERIAL_TX_PIN - #define E6_SERIAL_TX_PIN -1 + #define E6_SERIAL_TX_PIN -1 #endif #ifndef E6_SERIAL_RX_PIN - #define E6_SERIAL_RX_PIN -1 + #define E6_SERIAL_RX_PIN -1 #endif #ifndef E7_SERIAL_TX_PIN - #define E7_SERIAL_TX_PIN -1 + #define E7_SERIAL_TX_PIN -1 #endif #ifndef E7_SERIAL_RX_PIN - #define E7_SERIAL_RX_PIN -1 + #define E7_SERIAL_RX_PIN -1 #endif #endif @@ -394,62 +394,62 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 65 - #define LCD_PINS_D5 66 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 64 + #define LCD_PINS_RS 40 + #define LCD_PINS_ENABLE 42 + #define LCD_PINS_D4 65 + #define LCD_PINS_D5 66 + #define LCD_PINS_D6 44 + #define LCD_PINS_D7 64 #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 25 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 25 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #endif #elif ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS 64 - #define LCD_PINS_ENABLE 44 - #define LCD_PINS_D4 63 - #define LCD_PINS_D5 40 - #define LCD_PINS_D6 42 - #define LCD_PINS_D7 65 + #define LCD_PINS_RS 64 + #define LCD_PINS_ENABLE 44 + #define LCD_PINS_D4 63 + #define LCD_PINS_D5 40 + #define LCD_PINS_D6 42 + #define LCD_PINS_D7 65 #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 25 // Set as output on init - #define LCD_PINS_RS 27 // Pull low for 1s to init + #define LCD_PINS_DC 25 // Set as output on init + #define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 17 - #define DOGLCD_SCK 23 - #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_CS 16 + #define DOGLCD_MOSI 17 + #define DOGLCD_SCK 23 + #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 29 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #endif #endif @@ -457,10 +457,10 @@ #if DISABLED(NEWPANEL) // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK 38 + //#define SHIFT_LD 42 + //#define SHIFT_OUT 40 + //#define SHIFT_EN 17 #endif #endif @@ -472,85 +472,85 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 17 - #define BTN_EN2 23 + #define BTN_EN1 17 + #define BTN_EN2 23 #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 31 + #define BTN_EN2 33 #endif - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 + #define LCD_BACKLIGHT_PIN 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS SDSS - #define KILL_PIN 41 + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS SDSS + #define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 + #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_ENC -1 - #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 + #define LCD_SDSS SDSS + #define SD_DETECT_PIN 49 #elif ANY(VIKI2, miniVIKI) - #define DOGLCD_CS 45 - #define DOGLCD_A0 44 + #define DOGLCD_CS 45 + #define DOGLCD_A0 44 #define LCD_SCREEN_ROT_180 - #define BEEPER_PIN 33 - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define BEEPER_PIN 33 + #define STAT_LED_RED_PIN 32 + #define STAT_LED_BLUE_PIN 35 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 31 + #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board + #define KILL_PIN 31 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 - #define BEEPER_PIN 23 - #define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN 23 + #define LCD_BACKLIGHT_PIN 33 - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 - #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define LCD_SDSS SDSS + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 27 - #define DOGLCD_CS 25 + #define DOGLCD_A0 27 + #define DOGLCD_CS 25 // GLCD features // Uncomment screen orientation @@ -558,25 +558,25 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 // not connected to a pin - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 64 + #define SD_DETECT_PIN 49 + #define KILL_PIN 64 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // not connected to a pin - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 // GLCD features // Uncomment screen orientation @@ -584,16 +584,16 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 - #define SD_DETECT_PIN 49 - #define KILL_PIN 64 + #define SD_DETECT_PIN 49 + #define KILL_PIN 64 #elif ENABLED(ZONESTAR_LCD) - #define ADC_KEYPAD_PIN 12 + #define ADC_KEYPAD_PIN 12 #elif ENABLED(AZSMZ_12864) @@ -602,29 +602,29 @@ #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #endif #endif diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index ef064694ab..1417fb7d99 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -40,84 +40,84 @@ // // Servos // -#define SERVO0_PIN P1_23 +#define SERVO0_PIN P1_23 // // Limit Switches // -#define X_MIN_PIN P1_24 -#define Y_MIN_PIN P1_26 -#define Z_MIN_PIN P1_28 -#define Z_MAX_PIN P1_29 +#define X_MIN_PIN P1_24 +#define Y_MIN_PIN P1_26 +#define Z_MIN_PIN P1_28 +#define Z_MAX_PIN P1_29 // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 // A0 (TH1) -#define TEMP_BED_PIN P0_24_A1 // A1 (TH2) -#define TEMP_1_PIN P0_25_A2 // A2 (TH3) +#define TEMP_0_PIN P0_23_A0 // A0 (TH1) +#define TEMP_BED_PIN P0_24_A1 // A1 (TH2) +#define TEMP_1_PIN P0_25_A2 // A2 (TH3) // // Heaters / Fans // // EFB -#define HEATER_0_PIN P2_04 -#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_04 +#define HEATER_BED_PIN P2_05 #ifndef FAN_PIN - #define FAN_PIN P2_07 + #define FAN_PIN P2_07 #endif -#define FAN1_PIN P0_26 +#define FAN1_PIN P0_26 -#define LCD_SDSS P0_16 // LCD SD chip select -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define LCD_SDSS P0_16 // LCD SD chip select +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if ENABLED(AZSMZ_12864) - #define BEEPER_PIN P1_30 - #define DOGLCD_A0 P2_06 - #define DOGLCD_CS P1_22 - #define BTN_EN1 P4_28 - #define BTN_EN2 P1_27 - #define BTN_ENC P3_26 + #define BEEPER_PIN P1_30 + #define DOGLCD_A0 P2_06 + #define DOGLCD_CS P1_22 + #define BTN_EN1 P4_28 + #define BTN_EN2 P1_27 + #define BTN_ENC P3_26 #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #endif #endif #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - #define SS_PIN LCD_SDSS - #define SD_DETECT_PIN P3_25 + #define SCK_PIN P0_15 + #define MISO_PIN P0_17 + #define MOSI_PIN P0_18 + #define SS_PIN LCD_SDSS + #define SD_DETECT_PIN P3_25 #elif SD_CONNECTION_IS(ONBOARD) - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif @@ -125,16 +125,16 @@ // // Ethernet pins // -#define ENET_MDIO P1_17 -#define ENET_RX_ER P1_14 -#define ENET_RXD1 P1_10 -#define ENET_MOC P1_16 -#define REF_CLK P1_15 -#define ENET_RXD0 P1_09 -#define ENET_CRS P1_08 -#define ENET_TX_EN P1_04 -#define ENET_TXD0 P1_00 -#define ENET_TXD1 P1_01 +#define ENET_MDIO P1_17 +#define ENET_RX_ER P1_14 +#define ENET_RXD1 P1_10 +#define ENET_MOC P1_16 +#define REF_CLK P1_15 +#define ENET_RXD0 P1_09 +#define ENET_CRS P1_08 +#define ENET_TX_EN P1_04 +#define ENET_TXD0 P1_00 +#define ENET_TXD1 P1_01 /** * PWMs diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index a4800dcc73..d710138b95 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -47,42 +47,42 @@ // // Limit Switches // -#define X_MIN_PIN P1_24 // 10k pullup to 3.3V, 1K series -#define X_MAX_PIN P1_25 // 10k pullup to 3.3V, 1K series -#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V, 1K series -#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V, 1K series -#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V, 1K series -#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V, 1K series +#define X_MIN_PIN P1_24 // 10k pullup to 3.3V, 1K series +#define X_MAX_PIN P1_25 // 10k pullup to 3.3V, 1K series +#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V, 1K series +#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V, 1K series +#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V, 1K series +#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V, 1K series // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 #ifndef X_CS_PIN - #define X_CS_PIN P1_15 // ETH + #define X_CS_PIN P1_15 // ETH #endif -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 #ifndef Y_CS_PIN - #define Y_CS_PIN P1_14 // ETH + #define Y_CS_PIN P1_14 // ETH #endif -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 #ifndef Z_CS_PIN - #define Z_CS_PIN P1_16 // ETH + #define Z_CS_PIN P1_16 // ETH #endif -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 #ifndef E0_CS_PIN - #define E0_CS_PIN P1_17 // ETH + #define E0_CS_PIN P1_17 // ETH #endif // @@ -90,13 +90,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_18 // ETH + #define TMC_SW_MOSI P0_18 // ETH #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_17 // ETH + #define TMC_SW_MISO P0_17 // ETH #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_15 // ETH + #define TMC_SW_SCK P0_15 // ETH #endif #endif @@ -104,23 +104,23 @@ // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_24_A1 // A0 (T0) -#define TEMP_BED_PIN P0_23_A0 // A1 (T1) +#define TEMP_0_PIN P0_24_A1 // A0 (T0) +#define TEMP_BED_PIN P0_23_A0 // A1 (T1) // // Heaters / Fans // -#define HEATER_0_PIN P2_07 -#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 +#define HEATER_BED_PIN P2_05 #ifndef FAN_PIN - #define FAN_PIN P2_04 + #define FAN_PIN P2_04 #endif // // Unused // -//#define PIN_P2_10 P2_10 // IBOOT-1 -//#define PIN_P0_27 P0_27 // Onboard SD Detect +//#define PIN_P2_10 P2_10 // IBOOT-1 +//#define PIN_P0_27 P0_27 // Onboard SD Detect /** * LCD / Controller @@ -134,16 +134,16 @@ */ #if HAS_SPI_LCD - #define BEEPER_PIN P1_31 // EXP1-1 + #define BEEPER_PIN P1_31 // EXP1-1 - #define BTN_EN1 P3_26 // EXP2-3 - #define BTN_EN2 P3_25 // EXP2-5 - #define BTN_ENC P1_30 // EXP1-2 + #define BTN_EN1 P3_26 // EXP2-3 + #define BTN_EN2 P3_25 // EXP2-5 + #define BTN_ENC P1_30 // EXP1-2 - #define SD_DETECT_PIN P0_27 // EXP2-7 - #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 - #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 + #define SD_DETECT_PIN P0_27 // EXP2-7 + #define LCD_PINS_RS P0_16 // EXP1-4 + #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 + #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && HAS_CHARACTER_LCD #error "REPRAP_DISCOUNT_SMART_CONTROLLER is not supported by the BIQU B300 v1.0" @@ -162,11 +162,11 @@ * Hardware SPI can't be used because P0_17 (MISO) is not brought out on this board. */ #if ENABLED(SDSUPPORT) - #define SCK_PIN P0_15 // EXP1-5 - #define MISO_PIN P0_16 // EXP1-4 - #define MOSI_PIN P0_18 // EXP1-3 - #define SS_PIN P1_30 // EXP1-2 - #define SDSS SS_PIN + #define SCK_PIN P0_15 // EXP1-5 + #define MISO_PIN P0_16 // EXP1-4 + #define MOSI_PIN P0_18 // EXP1-3 + #define SS_PIN P1_30 // EXP1-2 + #define SDSS SS_PIN #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index 549b44019a..041235d493 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -45,56 +45,53 @@ // // Limit Switches // -#define X_MIN_PIN P1_24 // 10k pullup to 3.3V, 1K series -#define X_MAX_PIN P1_25 // 10k pullup to 3.3V, 1K series -#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V, 1K series -#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V, 1K series -#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V, 1K series -#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V, 1K series - +#define X_MIN_PIN P1_24 // 10k pullup to 3.3V, 1K series +#define X_MAX_PIN P1_25 // 10k pullup to 3.3V, 1K series +#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V, 1K series +#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V, 1K series +#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V, 1K series +#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V, 1K series // // Steppers // -#define X_STEP_PIN P2_0 -#define X_DIR_PIN P0_5 -#define X_ENABLE_PIN P0_4 +#define X_STEP_PIN P2_0 +#define X_DIR_PIN P0_5 +#define X_ENABLE_PIN P0_4 -#define Y_STEP_PIN P2_1 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 +#define Y_STEP_PIN P2_1 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 -#define Z_STEP_PIN P2_2 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 - -#define E0_STEP_PIN P2_3 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 +#define Z_STEP_PIN P2_2 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 +#define E0_STEP_PIN P2_3 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 // A0 (T0) -#define TEMP_BED_PIN P0_24_A1 // A1 (T1) - +#define TEMP_0_PIN P0_23_A0 // A0 (T0) +#define TEMP_BED_PIN P0_24_A1 // A1 (T1) // // Heaters / Fans // -#define HEATER_0_PIN P2_7 -#define HEATER_BED_PIN P2_5 +#define HEATER_0_PIN P2_7 +#define HEATER_BED_PIN P2_5 #ifndef FAN_PIN - #define FAN_PIN P2_4 + #define FAN_PIN P2_4 #endif // // Unused // -//#define PIN_P2_10 P2_10 // IBOOT-1 -//#define PIN_P0_27 P0_27 // Onboard SD Detect +//#define PIN_P2_10 P2_10 // IBOOT-1 +//#define PIN_P0_27 P0_27 // Onboard SD Detect /** * LCD / Controller @@ -108,16 +105,16 @@ */ #if HAS_SPI_LCD - #define BEEPER_PIN P1_31 // EXP1-1 + #define BEEPER_PIN P1_31 // EXP1-1 - #define BTN_EN1 P3_26 // EXP2-3 - #define BTN_EN2 P3_25 // EXP2-5 - #define BTN_ENC P1_30 // EXP1-2 + #define BTN_EN1 P3_26 // EXP2-3 + #define BTN_EN2 P3_25 // EXP2-5 + #define BTN_ENC P1_30 // EXP1-2 - #define SD_DETECT_PIN P0_27 // EXP2-7 - #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 - #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 + #define SD_DETECT_PIN P0_27 // EXP2-7 + #define LCD_PINS_RS P0_16 // EXP1-4 + #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 + #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && HAS_CHARACTER_LCD #error "REPRAP_DISCOUNT_SMART_CONTROLLER is not supported by the BIQU BQ111-A4" @@ -129,7 +126,6 @@ #endif // HAS_SPI_LCD - /** * SD Card Reader * @@ -138,15 +134,14 @@ */ #if ENABLED(SDSUPPORT) - #define SCK_PIN P0_15 // EXP1-5 - #define MISO_PIN P0_16 // EXP1-4 - #define MOSI_PIN P0_18 // EXP1-3 - #define SS_PIN P1_30 // EXP1-2 - #define SDSS SS_PIN + #define SCK_PIN P0_15 // EXP1-5 + #define MISO_PIN P0_16 // EXP1-4 + #define MOSI_PIN P0_18 // EXP1-3 + #define SS_PIN P1_30 // EXP1-2 + #define SDSS SS_PIN #endif // SDSUPPORT - /** * PWMS * diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index feadafa592..4dae2dc5d6 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -33,31 +33,31 @@ // Limit Switches // -#define X_MIN_PIN P1_29 -#define X_MAX_PIN P1_28 -#define Y_MIN_PIN P1_27 -#define Y_MAX_PIN P1_26 -#define Z_MIN_PIN P1_25 -#define Z_MAX_PIN P1_24 +#define X_MIN_PIN P1_29 +#define X_MAX_PIN P1_28 +#define Y_MIN_PIN P1_27 +#define Y_MAX_PIN P1_26 +#define Z_MIN_PIN P1_25 +#define Z_MAX_PIN P1_24 // // Steppers // -#define X_STEP_PIN P0_04 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P4_28 +#define X_STEP_PIN P0_04 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P4_28 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P2_02 -#define Y_ENABLE_PIN P2_00 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P2_02 +#define Y_ENABLE_PIN P2_00 -#define Z_STEP_PIN P0_20 -#define Z_DIR_PIN P0_21 -#define Z_ENABLE_PIN P0_19 +#define Z_STEP_PIN P0_20 +#define Z_DIR_PIN P0_21 +#define Z_ENABLE_PIN P0_19 -#define E0_STEP_PIN P0_11 -#define E0_DIR_PIN P2_13 -#define E0_ENABLE_PIN P2_12 +#define E0_STEP_PIN P0_11 +#define E0_DIR_PIN P2_13 +#define E0_ENABLE_PIN P2_12 /** * LCD / Controller @@ -73,19 +73,19 @@ */ #if HAS_SPI_LCD - #define BTN_EN1 P3_26 - #define BTN_EN2 P3_25 - #define BTN_ENC P2_11 + #define BTN_EN1 P3_26 + #define BTN_EN2 P3_25 + #define BTN_ENC P2_11 - #define SD_DETECT_PIN P1_31 - #define LCD_SDSS P1_23 - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 + #define SD_DETECT_PIN P1_31 + #define LCD_SDSS P1_23 + #define LCD_PINS_RS P0_16 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS P2_06 - #define DOGLCD_A0 P0_16 + #define DOGLCD_CS P2_06 + #define DOGLCD_A0 P0_16 #endif #endif @@ -97,14 +97,14 @@ // https://www.facebook.com/groups/505736576548648/permalink/630639874058317/ #ifndef SDCARD_CONNECTION #if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #else - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #endif #if SD_CONNECTION_IS(LCD) - #define SS_PIN P1_23 + #define SS_PIN P1_23 #endif // Trinamic driver support @@ -137,49 +137,48 @@ // When using any TMC SPI-based drivers, software SPI is used // because pins may be shared with the display or SD card. #define TMC_USE_SW_SPI - #define TMC_SW_MOSI P0_18 - #define TMC_SW_MISO P0_17 + #define TMC_SW_MOSI P0_18 + #define TMC_SW_MISO P0_17 // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SW_SCK P0_15 + #define TMC_SW_SCK P0_15 // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. - //#define TMC_SW_SCK P2_06 + //#define TMC_SW_SCK P2_06 #if ENABLED(SOFTWARE_DRIVER_ENABLE) // Software enable allows the enable pins to be repurposed as chip-select pins. // Note: Requires the driver modules to be modified to always be enabled with the enable pin removed. #if AXIS_DRIVER_TYPE_X(TMC2130) - #define X_CS_PIN P4_28 - #undef X_ENABLE_PIN - #define X_ENABLE_PIN -1 + #define X_CS_PIN P4_28 + #undef X_ENABLE_PIN + #define X_ENABLE_PIN -1 #endif #if AXIS_DRIVER_TYPE_Y(TMC2130) - #define Y_CS_PIN P2_00 - #undef Y_ENABLE_PIN - #define Y_ENABLE_PIN -1 + #define Y_CS_PIN P2_00 + #undef Y_ENABLE_PIN + #define Y_ENABLE_PIN -1 #endif #if AXIS_DRIVER_TYPE_Z(TMC2130) - #define Z_CS_PIN P0_19 - #undef Z_ENABLE_PIN - #define Z_ENABLE_PIN -1 + #define Z_CS_PIN P0_19 + #undef Z_ENABLE_PIN + #define Z_ENABLE_PIN -1 #endif #if AXIS_DRIVER_TYPE_E0(TMC2130) - #define E0_CS_PIN P2_12 - #undef E0_ENABLE_PIN - #define E0_ENABLE_PIN -1 + #define E0_CS_PIN P2_12 + #undef E0_ENABLE_PIN + #define E0_ENABLE_PIN -1 #endif - #if AXIS_DRIVER_TYPE_E1(TMC2130) - #define E1_CS_PIN P0_10 - #undef E1_ENABLE_PIN - #define E1_ENABLE_PIN -1 + #define E1_CS_PIN P0_10 + #undef E1_ENABLE_PIN + #define E1_ENABLE_PIN -1 #endif - #else // !SOFTWARE_DRIVER_ENABLE + #else // !SOFTWARE_DRIVER_ENABLE // A chip-select pin is needed for each driver. @@ -192,11 +191,11 @@ #if SD_CONNECTION_IS(LCD) #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_PINS_FOR_CS." #endif - #define X_CS_PIN P1_23 - #define Y_CS_PIN P3_26 - #define Z_CS_PIN P2_11 - #define E0_CS_PIN P3_25 - #define E1_CS_PIN P1_31 + #define X_CS_PIN P1_23 + #define Y_CS_PIN P3_26 + #define Z_CS_PIN P2_11 + #define E0_CS_PIN P3_25 + #define E1_CS_PIN P1_31 #endif // Example 2: A REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER @@ -207,16 +206,16 @@ #if SD_CONNECTION_IS(LCD) #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_SD_CARD_PINS_FOR_CS." #endif - #define X_CS_PIN P0_02 - #define Y_CS_PIN P0_03 - #define Z_CS_PIN P2_06 + #define X_CS_PIN P0_02 + #define Y_CS_PIN P0_03 + #define Z_CS_PIN P2_06 // We use SD_DETECT_PIN for E0 #undef SD_DETECT_PIN - #define E0_CS_PIN P1_31 + #define E0_CS_PIN P1_31 // We use LCD_SDSS pin for E1 - #undef LCD_SDSS - #define LCD_SDSS -1 - #define E1_CS_PIN P1_23 + #undef LCD_SDSS + #define LCD_SDSS -1 + #define E1_CS_PIN P1_23 #endif // Example 3: Use the driver enable pins for chip-select. @@ -224,11 +223,11 @@ // advanced features (like driver monitoring) will not be available. //#define SKR_USE_ENABLE_CS #if ENABLED(SKR_USE_ENABLE_FOR_CS) - #define X_CS_PIN X_ENABLE_PIN - #define Y_CS_PIN Y_ENABLE_PIN - #define Z_CS_PIN Z_ENABLE_PIN - #define E0_CS_PIN E0_ENABLE_PIN - #define E1_CS_PIN E1_ENABLE_PIN + #define X_CS_PIN X_ENABLE_PIN + #define Y_CS_PIN Y_ENABLE_PIN + #define Z_CS_PIN Z_ENABLE_PIN + #define E0_CS_PIN E0_ENABLE_PIN + #define E1_CS_PIN E1_ENABLE_PIN #endif #endif // SOFTWARE_DRIVER_ENABLE diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index adf726f024..1d1ad60f24 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -32,107 +32,107 @@ /** * Trinamic Stallguard pins */ -#define X_DIAG_PIN P1_29 // X- -#define Y_DIAG_PIN P1_27 // Y- -#define Z_DIAG_PIN P1_25 // Z- -#define E0_DIAG_PIN P1_28 // X+ -#define E1_DIAG_PIN P1_26 // Y+ +#define X_DIAG_PIN P1_29 // X- +#define Y_DIAG_PIN P1_27 // Y- +#define Z_DIAG_PIN P1_25 // Z- +#define E0_DIAG_PIN P1_28 // X+ +#define E1_DIAG_PIN P1_26 // Y+ /** * Limit Switches */ #if X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN + #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 - #define X_MAX_PIN P1_28 // X+ + #define X_MAX_PIN P1_28 // X+ #else - #define X_MIN_PIN P1_28 // X+ + #define X_MIN_PIN P1_28 // X+ #endif #else - #define X_MIN_PIN P1_29 // X- - #define X_MAX_PIN P1_28 // X+ + #define X_MIN_PIN P1_29 // X- + #define X_MAX_PIN P1_28 // X+ #endif #if Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN + #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 - #define Y_MAX_PIN P1_26 // Y+ + #define Y_MAX_PIN P1_26 // Y+ #else - #define Y_MIN_PIN P1_26 // Y+ + #define Y_MIN_PIN P1_26 // Y+ #endif #else - #define Y_MIN_PIN P1_27 // Y- - #define Y_MAX_PIN P1_26 // Y+ + #define Y_MIN_PIN P1_27 // Y- + #define Y_MAX_PIN P1_26 // Y+ #endif #if Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN + #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 - #define Z_MAX_PIN P1_24 // Z+ + #define Z_MAX_PIN P1_24 // Z+ #else - #define Z_MIN_PIN P1_24 // Z+ + #define Z_MIN_PIN P1_24 // Z+ #endif #else - #define Z_MIN_PIN P1_25 // Z- - #define Z_MAX_PIN P1_24 // Z+ + #define Z_MIN_PIN P1_25 // Z- + #define Z_MAX_PIN P1_24 // Z+ #endif -#define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups +#define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups // // Servos // #ifndef SERVO0_PIN - #define SERVO0_PIN P2_00 + #define SERVO0_PIN P2_00 #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN P1_24 + #define Z_MIN_PROBE_PIN P1_24 #endif // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN P1_28 + #define FIL_RUNOUT_PIN P1_28 #endif // // Steppers // -#define X_STEP_PIN P2_02 -#define X_DIR_PIN P2_06 -#define X_ENABLE_PIN P2_01 +#define X_STEP_PIN P2_02 +#define X_DIR_PIN P2_06 +#define X_ENABLE_PIN P2_01 #ifndef X_CS_PIN - #define X_CS_PIN P1_17 + #define X_CS_PIN P1_17 #endif -#define Y_STEP_PIN P0_19 -#define Y_DIR_PIN P0_20 -#define Y_ENABLE_PIN P2_08 +#define Y_STEP_PIN P0_19 +#define Y_DIR_PIN P0_20 +#define Y_ENABLE_PIN P2_08 #ifndef Y_CS_PIN - #define Y_CS_PIN P1_15 + #define Y_CS_PIN P1_15 #endif -#define Z_STEP_PIN P0_22 -#define Z_DIR_PIN P2_11 -#define Z_ENABLE_PIN P0_21 +#define Z_STEP_PIN P0_22 +#define Z_DIR_PIN P2_11 +#define Z_ENABLE_PIN P0_21 #ifndef Z_CS_PIN - #define Z_CS_PIN P1_10 + #define Z_CS_PIN P1_10 #endif -#define E0_STEP_PIN P2_13 -#define E0_DIR_PIN P0_11 -#define E0_ENABLE_PIN P2_12 +#define E0_STEP_PIN P2_13 +#define E0_DIR_PIN P0_11 +#define E0_ENABLE_PIN P2_12 #ifndef E0_CS_PIN - #define E0_CS_PIN P1_08 + #define E0_CS_PIN P1_08 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN P1_01 + #define E1_CS_PIN P1_01 #endif // @@ -140,13 +140,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P4_28 + #define TMC_SW_MOSI P4_28 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 + #define TMC_SW_MISO P0_05 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 + #define TMC_SW_SCK P0_04 #endif #endif @@ -172,20 +172,20 @@ // // Software serial // - #define X_SERIAL_TX_PIN P4_29 - #define X_SERIAL_RX_PIN P1_17 + #define X_SERIAL_TX_PIN P4_29 + #define X_SERIAL_RX_PIN P1_17 - #define Y_SERIAL_TX_PIN P1_16 - #define Y_SERIAL_RX_PIN P1_15 + #define Y_SERIAL_TX_PIN P1_16 + #define Y_SERIAL_RX_PIN P1_15 - #define Z_SERIAL_TX_PIN P1_14 - #define Z_SERIAL_RX_PIN P1_10 + #define Z_SERIAL_TX_PIN P1_14 + #define Z_SERIAL_RX_PIN P1_10 - #define E0_SERIAL_TX_PIN P1_09 - #define E0_SERIAL_RX_PIN P1_08 + #define E0_SERIAL_TX_PIN P1_09 + #define E0_SERIAL_RX_PIN P1_08 - #define E1_SERIAL_TX_PIN P1_04 - #define E1_SERIAL_RX_PIN P1_01 + #define E1_SERIAL_TX_PIN P1_04 + #define E1_SERIAL_RX_PIN P1_01 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -202,23 +202,23 @@ * EXP2 EXP1 */ -#define EXPA1_03_PIN P1_23 -#define EXPA1_04_PIN P1_22 -#define EXPA1_05_PIN P1_21 -#define EXPA1_06_PIN P1_20 -#define EXPA1_07_PIN P1_19 -#define EXPA1_08_PIN P1_18 -#define EXPA1_09_PIN P0_28 -#define EXPA1_10_PIN P1_30 +#define EXPA1_03_PIN P1_23 +#define EXPA1_04_PIN P1_22 +#define EXPA1_05_PIN P1_21 +#define EXPA1_06_PIN P1_20 +#define EXPA1_07_PIN P1_19 +#define EXPA1_08_PIN P1_18 +#define EXPA1_09_PIN P0_28 +#define EXPA1_10_PIN P1_30 -#define EXPA2_03_PIN -1 -#define EXPA2_04_PIN P1_31 -#define EXPA2_05_PIN P0_18 -#define EXPA2_06_PIN P3_25 -#define EXPA2_07_PIN P0_16 -#define EXPA2_08_PIN P3_26 -#define EXPA2_09_PIN P0_15 -#define EXPA2_10_PIN P0_17 +#define EXPA2_03_PIN -1 +#define EXPA2_04_PIN P1_31 +#define EXPA2_05_PIN P0_18 +#define EXPA2_06_PIN P3_25 +#define EXPA2_07_PIN P0_16 +#define EXPA2_08_PIN P3_26 +#define EXPA2_09_PIN P0_15 +#define EXPA2_10_PIN P0_17 #if HAS_SPI_LCD @@ -247,75 +247,75 @@ * LCD LCD */ - #define LCD_PINS_RS EXPA1_03_PIN + #define LCD_PINS_RS EXPA1_03_PIN - #define BTN_EN1 EXPA1_06_PIN - #define BTN_EN2 EXPA1_04_PIN - #define BTN_ENC EXPA1_08_PIN + #define BTN_EN1 EXPA1_06_PIN + #define BTN_EN2 EXPA1_04_PIN + #define BTN_ENC EXPA1_08_PIN - #define LCD_PINS_ENABLE EXPA1_05_PIN - #define LCD_PINS_D4 EXPA1_07_PIN + #define LCD_PINS_ENABLE EXPA1_05_PIN + #define LCD_PINS_D4 EXPA1_07_PIN #elif ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_RS EXPA1_04_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN // (58) open-drain + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_ENABLE EXPA1_03_PIN + #define LCD_PINS_D4 EXPA1_05_PIN - #else // !CR10_STOCKDISPLAY + #else // !CR10_STOCKDISPLAY - #define LCD_PINS_RS EXPA1_07_PIN + #define LCD_PINS_RS EXPA1_07_PIN - #define BTN_EN1 EXPA2_08_PIN // (31) J3-2 & AUX-4 - #define BTN_EN2 EXPA2_06_PIN // (33) J3-4 & AUX-4 - #define BTN_ENC EXPA1_09_PIN // (58) open-drain + #define BTN_EN1 EXPA2_08_PIN // (31) J3-2 & AUX-4 + #define BTN_EN2 EXPA2_06_PIN // (33) J3-4 & AUX-4 + #define BTN_ENC EXPA1_09_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXPA1_08_PIN - #define LCD_PINS_D4 EXPA1_06_PIN + #define LCD_PINS_ENABLE EXPA1_08_PIN + #define LCD_PINS_D4 EXPA1_06_PIN - #define LCD_SDSS EXPA2_07_PIN // (16) J3-7 & AUX-4 - #define SD_DETECT_PIN EXPA2_04_PIN // (49) (NOT 5V tolerant) + #define LCD_SDSS EXPA2_07_PIN // (16) J3-7 & AUX-4 + #define SD_DETECT_PIN EXPA2_04_PIN // (49) (NOT 5V tolerant) #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXPA1_08_PIN - #define DOGLCD_A0 EXPA1_07_PIN - #define DOGLCD_SCK EXPA2_09_PIN - #define DOGLCD_MOSI EXPA2_05_PIN + #define DOGLCD_CS EXPA1_08_PIN + #define DOGLCD_A0 EXPA1_07_PIN + #define DOGLCD_SCK EXPA2_09_PIN + #define DOGLCD_MOSI EXPA2_05_PIN - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 - #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXPA1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXPA1_06_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXPA1_05_PIN + #define RGB_LED_R_PIN EXPA1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXPA1_04_PIN + #define RGB_LED_G_PIN EXPA1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXPA1_03_PIN + #define RGB_LED_B_PIN EXPA1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXPA1_05_PIN + #define NEOPIXEL_PIN EXPA1_05_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS EXPA1_05_PIN - #define DOGLCD_A0 EXPA1_04_PIN - #define DOGLCD_SCK EXPA2_09_PIN - #define DOGLCD_MOSI EXPA2_05_PIN + #define DOGLCD_CS EXPA1_05_PIN + #define DOGLCD_A0 EXPA1_04_PIN + #define DOGLCD_SCK EXPA2_09_PIN + #define DOGLCD_MOSI EXPA2_05_PIN #elif ENABLED(ENDER2_STOCKDISPLAY) @@ -331,21 +331,21 @@ * EXP1 */ - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN + #define DOGLCD_CS EXPA1_04_PIN + #define DOGLCD_A0 EXPA1_05_PIN + #define DOGLCD_SCK EXPA1_10_PIN + #define DOGLCD_MOSI EXPA1_03_PIN #define FORCE_SOFT_SPI - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #endif #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 EXPA1_05_PIN - #define LCD_PINS_D6 EXPA1_04_PIN - #define LCD_PINS_D7 EXPA1_03_PIN + #define LCD_PINS_D5 EXPA1_05_PIN + #define LCD_PINS_D6 EXPA1_04_PIN + #define LCD_PINS_D7 EXPA1_03_PIN #endif #endif // !FYSETC_MINI_12864 @@ -359,11 +359,11 @@ // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #endif #if SD_CONNECTION_IS(LCD) - #define SS_PIN EXPA2_07_PIN + #define SS_PIN EXPA2_07_PIN #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 00c66521e6..7e722ea45f 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -37,58 +37,58 @@ // SD Connection // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #endif // // Servos // -#define SERVO0_PIN P2_00 +#define SERVO0_PIN P2_00 // // TMC StallGuard DIAG pins // -#define X_DIAG_PIN P1_29 // X-STOP -#define Y_DIAG_PIN P1_28 // Y-STOP -#define Z_DIAG_PIN P1_27 // Z-STOP -#define E0_DIAG_PIN P1_26 // E0DET -#define E1_DIAG_PIN P1_25 // E1DET +#define X_DIAG_PIN P1_29 // X-STOP +#define Y_DIAG_PIN P1_28 // Y-STOP +#define Z_DIAG_PIN P1_27 // Z-STOP +#define E0_DIAG_PIN P1_26 // E0DET +#define E1_DIAG_PIN P1_25 // E1DET // // Limit Switches // #if X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN + #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 - #define X_MAX_PIN P1_26 // E0DET + #define X_MAX_PIN P1_26 // E0DET #else - #define X_MIN_PIN P1_26 // E0DET + #define X_MIN_PIN P1_26 // E0DET #endif #else - #define X_STOP_PIN P1_29 // X-STOP + #define X_STOP_PIN P1_29 // X-STOP #endif #if Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN + #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 - #define Y_MAX_PIN P1_25 // E1DET + #define Y_MAX_PIN P1_25 // E1DET #else - #define Y_MIN_PIN P1_25 // E1DET + #define Y_MIN_PIN P1_25 // E1DET #endif #else - #define Y_STOP_PIN P1_28 // Y-STOP + #define Y_STOP_PIN P1_28 // Y-STOP #endif #if Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN + #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 - #define Z_MAX_PIN P1_00 // PWRDET + #define Z_MAX_PIN P1_00 // PWRDET #else - #define Z_MIN_PIN P1_00 // PWRDET + #define Z_MIN_PIN P1_00 // PWRDET #endif #else #ifndef Z_STOP_PIN - #define Z_STOP_PIN P1_27 // Z-STOP + #define Z_STOP_PIN P1_27 // Z-STOP #endif #endif @@ -96,82 +96,82 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN P0_10 + #define Z_MIN_PROBE_PIN P0_10 #endif // // Filament Runout Sensor // -#define FIL_RUNOUT_PIN P1_26 // E0DET -#define FIL_RUNOUT2_PIN P1_25 // E1DET +#define FIL_RUNOUT_PIN P1_26 // E0DET +#define FIL_RUNOUT2_PIN P1_25 // E1DET // // Power Supply Control // #ifndef PS_ON_PIN - #define PS_ON_PIN P1_00 // PWRDET + #define PS_ON_PIN P1_00 // PWRDET #endif // // Power Loss Detection // #ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN P1_00 // PWRDET + #define POWER_LOSS_PIN P1_00 // PWRDET #endif // // Steppers // -#define X_STEP_PIN P2_02 -#define X_DIR_PIN P2_06 -#define X_ENABLE_PIN P2_01 +#define X_STEP_PIN P2_02 +#define X_DIR_PIN P2_06 +#define X_ENABLE_PIN P2_01 #ifndef X_CS_PIN - #define X_CS_PIN P1_10 + #define X_CS_PIN P1_10 #endif -#define Y_STEP_PIN P0_19 -#define Y_DIR_PIN P0_20 -#define Y_ENABLE_PIN P2_08 +#define Y_STEP_PIN P0_19 +#define Y_DIR_PIN P0_20 +#define Y_ENABLE_PIN P2_08 #ifndef Y_CS_PIN - #define Y_CS_PIN P1_09 + #define Y_CS_PIN P1_09 #endif -#define Z_STEP_PIN P0_22 -#define Z_DIR_PIN P2_11 -#define Z_ENABLE_PIN P0_21 +#define Z_STEP_PIN P0_22 +#define Z_DIR_PIN P2_11 +#define Z_ENABLE_PIN P0_21 #ifndef Z_CS_PIN - #define Z_CS_PIN P1_08 + #define Z_CS_PIN P1_08 #endif -#define E0_STEP_PIN P2_13 -#define E0_DIR_PIN P0_11 -#define E0_ENABLE_PIN P2_12 +#define E0_STEP_PIN P2_13 +#define E0_DIR_PIN P0_11 +#define E0_ENABLE_PIN P2_12 #ifndef E0_CS_PIN - #define E0_CS_PIN P1_04 + #define E0_CS_PIN P1_04 #endif -#define E1_STEP_PIN P1_15 -#define E1_DIR_PIN P1_14 -#define E1_ENABLE_PIN P1_16 +#define E1_STEP_PIN P1_15 +#define E1_DIR_PIN P1_14 +#define E1_ENABLE_PIN P1_16 #ifndef E1_CS_PIN - #define E1_CS_PIN P1_01 + #define E1_CS_PIN P1_01 #endif -#define TEMP_1_PIN P0_23_A0 // A2 (T2) - (69) - TEMP_1_PIN -#define TEMP_BED_PIN P0_25_A2 // A0 (T0) - (67) - TEMP_BED_PIN +#define TEMP_1_PIN P0_23_A0 // A2 (T2) - (69) - TEMP_1_PIN +#define TEMP_BED_PIN P0_25_A2 // A0 (T0) - (67) - TEMP_BED_PIN // // Software SPI pins for TMC2130 stepper drivers // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_17 + #define TMC_SW_MOSI P1_17 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 + #define TMC_SW_MISO P0_05 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 + #define TMC_SW_SCK P0_04 #endif #endif @@ -197,23 +197,23 @@ // // Software serial // - #define X_SERIAL_TX_PIN P1_10 - #define X_SERIAL_RX_PIN P1_10 + #define X_SERIAL_TX_PIN P1_10 + #define X_SERIAL_RX_PIN P1_10 - #define Y_SERIAL_TX_PIN P1_09 - #define Y_SERIAL_RX_PIN P1_09 + #define Y_SERIAL_TX_PIN P1_09 + #define Y_SERIAL_RX_PIN P1_09 - #define Z_SERIAL_TX_PIN P1_08 - #define Z_SERIAL_RX_PIN P1_08 + #define Z_SERIAL_TX_PIN P1_08 + #define Z_SERIAL_RX_PIN P1_08 - #define E0_SERIAL_TX_PIN P1_04 - #define E0_SERIAL_RX_PIN P1_04 + #define E0_SERIAL_TX_PIN P1_04 + #define E0_SERIAL_RX_PIN P1_04 - #define E1_SERIAL_TX_PIN P1_01 - #define E1_SERIAL_RX_PIN P1_01 + #define E1_SERIAL_TX_PIN P1_01 + #define E1_SERIAL_RX_PIN P1_01 - #define Z2_SERIAL_TX_PIN P1_01 - #define Z2_SERIAL_RX_PIN P1_01 + #define Z2_SERIAL_TX_PIN P1_01 + #define Z2_SERIAL_RX_PIN P1_01 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -223,7 +223,7 @@ // SD Connection // #if SD_CONNECTION_IS(LCD) - #define SS_PIN P0_16 + #define SS_PIN P0_16 #endif /** @@ -239,82 +239,82 @@ #if HAS_SPI_LCD #if ENABLED(ANET_FULL_GRAPHICS_LCD) - #define LCD_PINS_RS P1_23 + #define LCD_PINS_RS P1_23 - #define BTN_EN1 P1_20 - #define BTN_EN2 P1_22 - #define BTN_ENC P1_18 + #define BTN_EN1 P1_20 + #define BTN_EN2 P1_22 + #define BTN_ENC P1_18 - #define LCD_PINS_ENABLE P1_21 - #define LCD_PINS_D4 P1_19 + #define LCD_PINS_ENABLE P1_21 + #define LCD_PINS_D4 P1_19 #elif ENABLED(CR10_STOCKDISPLAY) - #define BTN_ENC P0_28 // (58) open-drain - #define LCD_PINS_RS P1_22 + #define BTN_ENC P0_28 // (58) open-drain + #define LCD_PINS_RS P1_22 - #define BTN_EN1 P1_18 - #define BTN_EN2 P1_20 + #define BTN_EN1 P1_18 + #define BTN_EN2 P1_20 - #define LCD_PINS_ENABLE P1_23 - #define LCD_PINS_D4 P1_21 + #define LCD_PINS_ENABLE P1_23 + #define LCD_PINS_D4 P1_21 #else - #define BTN_ENC P0_28 // (58) open-drain - #define LCD_PINS_RS P1_19 + #define BTN_ENC P0_28 // (58) open-drain + #define LCD_PINS_RS P1_19 - #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 - #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 + #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 + #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 - #define LCD_PINS_ENABLE P1_18 - #define LCD_PINS_D4 P1_20 + #define LCD_PINS_ENABLE P1_18 + #define LCD_PINS_D4 P1_20 - #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 + #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN P1_31 // (49) (NOT 5V tolerant) + #define SD_DETECT_PIN P1_31 // (49) (NOT 5V tolerant) #endif #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS P1_18 - #define DOGLCD_A0 P1_19 - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_CS P1_18 + #define DOGLCD_A0 P1_19 + #define DOGLCD_SCK P0_15 + #define DOGLCD_MOSI P0_18 - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 - #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN P1_20 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN P1_20 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P1_21 + #define RGB_LED_R_PIN P1_21 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_22 + #define RGB_LED_G_PIN P1_22 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_23 + #define RGB_LED_B_PIN P1_23 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P1_21 + #define NEOPIXEL_PIN P1_21 #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS P1_21 - #define DOGLCD_A0 P1_22 - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_CS P1_21 + #define DOGLCD_A0 P1_22 + #define DOGLCD_SCK P0_15 + #define DOGLCD_MOSI P0_18 #define FORCE_SOFT_SPI #endif #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 P1_21 - #define LCD_PINS_D6 P1_22 - #define LCD_PINS_D7 P1_23 + #define LCD_PINS_D5 P1_21 + #define LCD_PINS_D6 P1_22 + #define LCD_PINS_D7 P1_23 #endif #endif // !FYSETC_MINI_12864 @@ -327,7 +327,7 @@ // Neopixel LED // #ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN P1_24 + #define NEOPIXEL_PIN P1_24 #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 2844fb3cda..63e160d8a0 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -40,13 +40,13 @@ // Steppers // #ifndef E1_STEP_PIN - #define E1_STEP_PIN P0_01 + #define E1_STEP_PIN P0_01 #endif #ifndef E1_DIR_PIN - #define E1_DIR_PIN P0_00 + #define E1_DIR_PIN P0_00 #endif #ifndef E1_ENABLE_PIN - #define E1_ENABLE_PIN P0_10 + #define E1_ENABLE_PIN P0_10 #endif // @@ -54,64 +54,64 @@ // 3.3V max when defined as an analog input // #ifndef TEMP_0_PIN - #define TEMP_0_PIN P0_24_A1 // A1 (T1) - (68) - TEMP_0_PIN + #define TEMP_0_PIN P0_24_A1 // A1 (T1) - (68) - TEMP_0_PIN #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_1_PIN + #define TEMP_1_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_1_PIN #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN + #define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN #endif #if HOTENDS == 1 && TEMP_SENSOR_PROBE - #define TEMP_PROBE_PIN TEMP_1_PIN + #define TEMP_PROBE_PIN TEMP_1_PIN #endif // // Heaters / Fans // #ifndef HEATER_0_PIN - #define HEATER_0_PIN P2_07 + #define HEATER_0_PIN P2_07 #endif #if HOTENDS == 1 #ifndef FAN1_PIN - #define FAN1_PIN P2_04 + #define FAN1_PIN P2_04 #endif #else #ifndef HEATER_1_PIN - #define HEATER_1_PIN P2_04 + #define HEATER_1_PIN P2_04 #endif #endif #ifndef FAN_PIN - #define FAN_PIN P2_03 + #define FAN_PIN P2_03 #endif #ifndef HEATER_BED_PIN - #define HEATER_BED_PIN P2_05 + #define HEATER_BED_PIN P2_05 #endif // // LCD / Controller // #if HAS_SPI_LCD - #define BEEPER_PIN P1_30 // (37) not 5V tolerant + #define BEEPER_PIN P1_30 // (37) not 5V tolerant #endif // // SD Support // -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 + #define SCK_PIN P0_15 + #define MISO_PIN P0_17 + #define MOSI_PIN P0_18 #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_DETECT_PIN P0_27 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 5ebf6ecba1..32de7bb740 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -44,63 +44,63 @@ // // Servos // -#define SERVO0_PIN P1_26 // PWM1[6] -#define SERVO1_PIN P1_18 // PWM1[1] +#define SERVO0_PIN P1_26 // PWM1[6] +#define SERVO1_PIN P1_18 // PWM1[1] // // Limit Switches // -#define X_MIN_PIN P0_00 -#define X_MAX_PIN P0_01 -#define Y_MIN_PIN P0_10 -#define Y_MAX_PIN P0_21 -#define Z_MIN_PIN P2_13 -#define Z_MAX_PIN P2_22 +#define X_MIN_PIN P0_00 +#define X_MAX_PIN P0_01 +#define Y_MIN_PIN P0_10 +#define Y_MAX_PIN P0_21 +#define Z_MIN_PIN P2_13 +#define Z_MAX_PIN P2_22 // // Steppers // -#define X_STEP_PIN P1_01 -#define X_DIR_PIN P1_04 -#define X_ENABLE_PIN P0_26 +#define X_STEP_PIN P1_01 +#define X_DIR_PIN P1_04 +#define X_ENABLE_PIN P0_26 -#define Y_STEP_PIN P1_10 -#define Y_DIR_PIN P1_14 -#define Y_ENABLE_PIN P1_08 +#define Y_STEP_PIN P1_10 +#define Y_DIR_PIN P1_14 +#define Y_ENABLE_PIN P1_08 -#define Z_STEP_PIN P1_17 -#define Z_DIR_PIN P4_29 -#define Z_ENABLE_PIN P1_15 +#define Z_STEP_PIN P1_17 +#define Z_DIR_PIN P4_29 +#define Z_ENABLE_PIN P1_15 -#define E0_STEP_PIN P0_05 -#define E0_DIR_PIN P2_00 -#define E0_ENABLE_PIN P4_28 +#define E0_STEP_PIN P0_05 +#define E0_DIR_PIN P2_00 +#define E0_ENABLE_PIN P4_28 -#define E1_STEP_PIN P2_03 -#define E1_DIR_PIN P2_04 -#define E1_ENABLE_PIN P2_01 +#define E1_STEP_PIN P2_03 +#define E1_DIR_PIN P2_04 +#define E1_ENABLE_PIN P2_01 -#define E2_STEP_PIN P2_07 -#define E2_DIR_PIN P2_08 -#define E2_ENABLE_PIN P2_05 +#define E2_STEP_PIN P2_07 +#define E2_DIR_PIN P2_08 +#define E2_ENABLE_PIN P2_05 // // TMC2208 UART pins // #if HAS_TMC_UART - #define X_SERIAL_TX_PIN P1_00 - #define X_SERIAL_RX_PIN P1_00 - #define Y_SERIAL_TX_PIN P1_09 - #define Y_SERIAL_RX_PIN P1_09 - #define Z_SERIAL_TX_PIN P1_16 - #define Z_SERIAL_RX_PIN P1_16 - #define E0_SERIAL_TX_PIN P0_04 - #define E0_SERIAL_RX_PIN P0_04 - #define E1_SERIAL_TX_PIN P2_02 - #define E1_SERIAL_RX_PIN P2_02 - #define E2_SERIAL_TX_PIN P2_06 - #define E2_SERIAL_RX_PIN P2_06 + #define X_SERIAL_TX_PIN P1_00 + #define X_SERIAL_RX_PIN P1_00 + #define Y_SERIAL_TX_PIN P1_09 + #define Y_SERIAL_RX_PIN P1_09 + #define Z_SERIAL_TX_PIN P1_16 + #define Z_SERIAL_RX_PIN P1_16 + #define E0_SERIAL_TX_PIN P0_04 + #define E0_SERIAL_RX_PIN P0_04 + #define E1_SERIAL_TX_PIN P2_02 + #define E1_SERIAL_RX_PIN P2_02 + #define E2_SERIAL_TX_PIN P2_06 + #define E2_SERIAL_RX_PIN P2_06 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -112,36 +112,36 @@ // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_24_A1 // AD0[0] on P0_23 -#define TEMP_BED_PIN P0_23_A0 // AD0[1] on P0_24 +#define TEMP_0_PIN P0_24_A1 // AD0[0] on P0_23 +#define TEMP_BED_PIN P0_23_A0 // AD0[1] on P0_24 // // Heaters / Fans // -#define HEATER_BED_PIN P1_19 // Not a PWM pin, software PWM required -#define HEATER_0_PIN P3_26 // PWM1[3] -#define FAN_PIN P3_25 // Part cooling fan - connected to PWM1[2] -#define E0_AUTO_FAN_PIN P0_27 // Extruder cooling fan +#define HEATER_BED_PIN P1_19 // Not a PWM pin, software PWM required +#define HEATER_0_PIN P3_26 // PWM1[3] +#define FAN_PIN P3_25 // Part cooling fan - connected to PWM1[2] +#define E0_AUTO_FAN_PIN P0_27 // Extruder cooling fan // // Misc. Functions // -#define LED_PIN P1_31 +#define LED_PIN P1_31 // // LCD // #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN P0_19 - #define BTN_EN1 P1_23 - #define BTN_EN2 P1_24 - #define BTN_ENC P1_25 - #define LCD_PINS_RS P0_20 - #define LCD_PINS_ENABLE P0_21 - #define LCD_PINS_D4 P2_11 - #define LCD_PINS_D5 P0_22 - #define LCD_PINS_D6 P1_29 - #define LCD_PINS_D7 P1_28 + #define BEEPER_PIN P0_19 + #define BTN_EN1 P1_23 + #define BTN_EN2 P1_24 + #define BTN_ENC P1_25 + #define LCD_PINS_RS P0_20 + #define LCD_PINS_ENABLE P0_21 + #define LCD_PINS_D4 P2_11 + #define LCD_PINS_D5 P0_22 + #define LCD_PINS_D6 P1_29 + #define LCD_PINS_D7 P1_28 #endif // @@ -149,21 +149,21 @@ // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - #define SS_PIN P0_16 + #define SCK_PIN P0_15 + #define MISO_PIN P0_17 + #define MOSI_PIN P0_18 + #define SS_PIN P0_16 #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_DETECT_PIN P0_27 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 28b94f019a..0cd10ebc05 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -46,73 +46,73 @@ //#define SDCARD_EEPROM_EMULATION #endif -#define LED_PIN P1_18 // Used as a status indicator -#define LED2_PIN P1_19 -#define LED3_PIN P1_20 -#define LED4_PIN P1_21 +#define LED_PIN P1_18 // Used as a status indicator +#define LED2_PIN P1_19 +#define LED3_PIN P1_20 +#define LED4_PIN P1_21 // // Servos // -#define SERVO0_PIN P1_23 // J8-3 (low jitter) -#define SERVO1_PIN P2_12 // J8-4 -#define SERVO2_PIN P2_11 // J8-5 -#define SERVO3_PIN P4_28 // J8-6 +#define SERVO0_PIN P1_23 // J8-3 (low jitter) +#define SERVO1_PIN P2_12 // J8-4 +#define SERVO2_PIN P2_11 // J8-5 +#define SERVO3_PIN P4_28 // J8-6 // // Limit Switches - Not Interrupt Capable // -#define X_MIN_PIN P1_24 // 10k pullup to 3.3V, 1K series -#define X_MAX_PIN P1_25 // 10k pullup to 3.3V, 1K series -#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V, 1K series -#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V, 1K series -#define Z_MIN_PIN P1_28 // The original Mks Sbase DIO19 has a 10k pullup to 3.3V or 5V, 1K series, so when using a Zprobe we must use DIO41 (J8 P1.22) -#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V, 1K series +#define X_MIN_PIN P1_24 // 10k pullup to 3.3V, 1K series +#define X_MAX_PIN P1_25 // 10k pullup to 3.3V, 1K series +#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V, 1K series +#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V, 1K series +#define Z_MIN_PIN P1_28 // The original Mks Sbase DIO19 has a 10k pullup to 3.3V or 5V, 1K series, so when using a Zprobe we must use DIO41 (J8 P1.22) +#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V, 1K series #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN P4_28 // Connector J8 + #define Z_MIN_PROBE_PIN P4_28 // Connector J8 #endif // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) -#define TEMP_0_PIN P0_24_A1 // A1 (TH2) -#define TEMP_1_PIN P0_25_A2 // A2 (TH3) -#define TEMP_2_PIN P0_26_A3 // A3 (TH4) +#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) +#define TEMP_0_PIN P0_24_A1 // A1 (TH2) +#define TEMP_1_PIN P0_25_A2 // A2 (TH3) +#define TEMP_2_PIN P0_26_A3 // A3 (TH4) // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_0_PIN P2_07 -#define HEATER_1_PIN P2_06 +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 +#define HEATER_1_PIN P2_06 #ifndef FAN_PIN - #define FAN_PIN P2_04 + #define FAN_PIN P2_04 #endif // @@ -124,56 +124,56 @@ // 5V // NC // GND -#define PIN_P0_17 P0_17 -#define PIN_P0_16 P0_16 -#define PIN_P0_15 P0_15 +#define PIN_P0_17 P0_17 +#define PIN_P0_16 P0_16 +#define PIN_P0_15 P0_15 // // Connector J8 // // GND -#define PIN_P1_22 P1_22 -#define PIN_P1_23 P1_23 // PWM Capable -#define PIN_P2_12 P2_12 // Interrupt Capable -#define PIN_P2_11 P2_11 // Interrupt Capable +#define PIN_P1_22 P1_22 +#define PIN_P1_23 P1_23 // PWM Capable +#define PIN_P2_12 P2_12 // Interrupt Capable +#define PIN_P2_11 P2_11 // Interrupt Capable // // Průša i3 MK2 Multi Material Multiplexer Support // #if ENABLED(MK2_MULTIPLEXER) - #define E_MUX0_PIN P1_23 // J8-3 - #define E_MUX1_PIN P2_12 // J8-4 - #define E_MUX2_PIN P2_11 // J8-5 + #define E_MUX0_PIN P1_23 // J8-3 + #define E_MUX1_PIN P2_12 // J8-4 + #define E_MUX2_PIN P2_11 // J8-5 #endif // // Misc. Functions // -#define PS_ON_PIN P0_25 // TH3 Connector +#define PS_ON_PIN P0_25 // TH3 Connector // // Ethernet pins // #ifndef ULTIPANEL - #define ENET_MDIO P1_17 // J12-4 - #define ENET_RX_ER P1_14 // J12-6 - #define ENET_RXD1 P1_10 // J12-8 + #define ENET_MDIO P1_17 // J12-4 + #define ENET_RX_ER P1_14 // J12-6 + #define ENET_RXD1 P1_10 // J12-8 #endif -#define ENET_MOC P1_16 // J12-3 -#define REF_CLK P1_15 // J12-5 -#define ENET_RXD0 P1_09 // J12-7 -#define ENET_CRS P1_08 // J12-9 -#define ENET_TX_EN P1_04 // J12-10 -#define ENET_TXD0 P1_00 // J12-11 -#define ENET_TXD1 P1_01 // J12-12 +#define ENET_MOC P1_16 // J12-3 +#define REF_CLK P1_15 // J12-5 +#define ENET_RXD0 P1_09 // J12-7 +#define ENET_CRS P1_08 // J12-9 +#define ENET_TX_EN P1_04 // J12-10 +#define ENET_TXD0 P1_00 // J12-11 +#define ENET_TXD1 P1_01 // J12-12 #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(CUSTOM_CABLE) @@ -189,27 +189,27 @@ * If you can't find a pin to use for the LCD's SD_DETECT then comment out * SD_DETECT_PIN entirely and remove that wire from the the custom cable. */ - #define SD_DETECT_PIN P2_11 // J8-5 (moved from EXP2 P0.27) - #define SCK_PIN P1_22 // J8-2 (moved from EXP2 P0.7) - #define MISO_PIN P1_23 // J8-3 (moved from EXP2 P0.8) - #define MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.9) - #define SS_PIN P0_28 - #define LPC_SOFTWARE_SPI // With a custom cable we need software SPI because the - // selected pins are not on a hardware SPI controller + #define SD_DETECT_PIN P2_11 // J8-5 (moved from EXP2 P0.27) + #define SCK_PIN P1_22 // J8-2 (moved from EXP2 P0.7) + #define MISO_PIN P1_23 // J8-3 (moved from EXP2 P0.8) + #define MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.9) + #define SS_PIN P0_28 + #define LPC_SOFTWARE_SPI // With a custom cable we need software SPI because the + // selected pins are not on a hardware SPI controller #elif SD_CONNECTION_IS(LCD) // use standard cable and header, SPI and SD detect sre shared with on-board SD card // hardware SPI is used for both SD cards. The detect pin is shred between the // LCD and onboard SD readers so we disable it. - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN P0_28 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN P0_28 #elif SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SD_DETECT_PIN P0_27 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #endif /** @@ -226,17 +226,17 @@ */ #if HAS_SPI_LCD - #define BEEPER_PIN P1_31 // EXP1.1 - #define BTN_ENC P1_30 // EXP1.2 - #define BTN_EN1 P3_26 // EXP2.5 - #define BTN_EN2 P3_25 // EXP2.3 - #define LCD_PINS_RS P0_16 // EXP1.4 - #define LCD_SDSS P0_28 // EXP2.4 - #define LCD_PINS_ENABLE P0_18 // EXP1.3 - #define LCD_PINS_D4 P0_15 // EXP1.5 + #define BEEPER_PIN P1_31 // EXP1.1 + #define BTN_ENC P1_30 // EXP1.2 + #define BTN_EN1 P3_26 // EXP2.5 + #define BTN_EN2 P3_25 // EXP2.3 + #define LCD_PINS_RS P0_16 // EXP1.4 + #define LCD_SDSS P0_28 // EXP2.4 + #define LCD_PINS_ENABLE P0_18 // EXP1.3 + #define LCD_PINS_D4 P0_15 // EXP1.5 #if ANY(VIKI2, miniVIKI) - #define DOGLCD_SCK SCK_PIN - #define DOGLCD_MOSI MOSI_PIN + #define DOGLCD_SCK SCK_PIN + #define DOGLCD_MOSI MOSI_PIN #endif #if ENABLED(FYSETC_MINI_12864) @@ -251,26 +251,26 @@ * Pins 6, 7 & 8 on EXP2 are no connects. That means a second special * cable will be needed if the RGB LEDs are to be active. */ - #define DOGLCD_CS LCD_PINS_ENABLE // EXP1.3 (LCD_EN on FYSETC schematic) - #define DOGLCD_A0 LCD_PINS_RS // EXP1.4 (LCD_A0 on FYSETC schematic) - #define DOGLCD_SCK P2_11 // J8-5 (SCK on FYSETC schematic) - #define DOGLCD_MOSI P4_28 // J8-6 (MOSI on FYSETC schematic) + #define DOGLCD_CS LCD_PINS_ENABLE // EXP1.3 (LCD_EN on FYSETC schematic) + #define DOGLCD_A0 LCD_PINS_RS // EXP1.4 (LCD_A0 on FYSETC schematic) + #define DOGLCD_SCK P2_11 // J8-5 (SCK on FYSETC schematic) + #define DOGLCD_MOSI P4_28 // J8-6 (MOSI on FYSETC schematic) - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P2_12 // J8-4 (LCD_D6 on FYSETC schematic) + #define RGB_LED_R_PIN P2_12 // J8-4 (LCD_D6 on FYSETC schematic) #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_23 // J8-3 (LCD_D5 on FYSETC schematic) + #define RGB_LED_G_PIN P1_23 // J8-3 (LCD_D5 on FYSETC schematic) #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_22 // J8-2 (LCD_D7 on FYSETC schematic) + #define RGB_LED_B_PIN P1_22 // J8-2 (LCD_D7 on FYSETC schematic) #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P2_12 + #define NEOPIXEL_PIN P2_12 #endif #elif ENABLED(MINIPANEL) @@ -291,24 +291,24 @@ #if HAS_DRIVER(TMC2130) // J8 - #define X_CS_PIN P1_22 - #define Y_CS_PIN P1_23 - #define Z_CS_PIN P2_12 - #define E0_CS_PIN P2_11 - #define E1_CS_PIN P4_28 + #define X_CS_PIN P1_22 + #define Y_CS_PIN P1_23 + #define Z_CS_PIN P2_12 + #define E0_CS_PIN P2_11 + #define E1_CS_PIN P4_28 // Hardware SPI is on EXP2. See if you can make it work: // https://github.com/makerbase-mks/MKS-SBASE/issues/25 #define TMC_USE_SW_SPI #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_03 // AUX1 + #define TMC_SW_MOSI P0_03 // AUX1 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_02 // AUX1 + #define TMC_SW_MISO P0_02 // AUX1 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_26 // TH4 + #define TMC_SW_SCK P0_26 // TH4 #endif #endif #endif @@ -322,24 +322,24 @@ * Worst case you may have to give up the LCD * RX pins need to be interrupt capable */ - #define X_SERIAL_TX_PIN P1_22 // J8-2 - #define X_SERIAL_RX_PIN P2_12 // J8-4 Interrupt Capable - #define Y_SERIAL_TX_PIN P1_23 // J8-3 - #define Y_SERIAL_RX_PIN P2_11 // J8-5 Interrupt Capable - #define Z_SERIAL_TX_PIN P2_12 // J8-4 - #define Z_SERIAL_RX_PIN P0_25 // TH3 - #define E0_SERIAL_TX_PIN P4_28 // J8-6 - #define E0_SERIAL_RX_PIN P0_26 // TH4 + #define X_SERIAL_TX_PIN P1_22 // J8-2 + #define X_SERIAL_RX_PIN P2_12 // J8-4 Interrupt Capable + #define Y_SERIAL_TX_PIN P1_23 // J8-3 + #define Y_SERIAL_RX_PIN P2_11 // J8-5 Interrupt Capable + #define Z_SERIAL_TX_PIN P2_12 // J8-4 + #define Z_SERIAL_RX_PIN P0_25 // TH3 + #define E0_SERIAL_TX_PIN P4_28 // J8-6 + #define E0_SERIAL_RX_PIN P0_26 // TH4 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 #endif // UNUSED -#define PIN_P0_27 P0_27 // EXP2/Onboard SD -#define PIN_P0_28 P0_28 // EXP2 -#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) -#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +#define PIN_P0_27 P0_27 // EXP2/Onboard SD +#define PIN_P0_28 P0_28 // EXP2 +#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) /** * PWMs diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 5dc1db8f3f..afbe6d5564 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -41,100 +41,100 @@ // // Servos // -#define SERVO0_PIN P1_23 // SERVO P1.23 -#define SERVO1_PIN P2_00 // SERVO P2.0 +#define SERVO0_PIN P1_23 // SERVO P1.23 +#define SERVO1_PIN P2_00 // SERVO P2.0 // // Trinamic Stallguard pins // -#define X_DIAG_PIN P1_29 // X- -#define Y_DIAG_PIN P1_27 // Y- -#define Z_DIAG_PIN P1_25 // Z- -#define E0_DIAG_PIN P1_28 // X+ -#define E1_DIAG_PIN P1_26 // Y+ +#define X_DIAG_PIN P1_29 // X- +#define Y_DIAG_PIN P1_27 // Y- +#define Z_DIAG_PIN P1_25 // Z- +#define E0_DIAG_PIN P1_28 // X+ +#define E1_DIAG_PIN P1_26 // Y+ // // Limit Switches // #if X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN + #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 - #define X_MAX_PIN P1_28 // X+ + #define X_MAX_PIN P1_28 // X+ #else - #define X_MIN_PIN P1_28 // X+ + #define X_MIN_PIN P1_28 // X+ #endif #else - #define X_MIN_PIN P1_29 // X- - #define X_MAX_PIN P1_28 // X+ + #define X_MIN_PIN P1_29 // X- + #define X_MAX_PIN P1_28 // X+ #endif #if Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN + #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 - #define Y_MAX_PIN P1_26 // Y+ + #define Y_MAX_PIN P1_26 // Y+ #else - #define Y_MIN_PIN P1_26 // Y+ + #define Y_MIN_PIN P1_26 // Y+ #endif #else - #define Y_MIN_PIN P1_27 // Y- - #define Y_MAX_PIN P1_26 // Y+ + #define Y_MIN_PIN P1_27 // Y- + #define Y_MAX_PIN P1_26 // Y+ #endif #if Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN + #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 - #define Z_MAX_PIN P1_24 // Z+ + #define Z_MAX_PIN P1_24 // Z+ #else - #define Z_MIN_PIN P1_24 // Z+ + #define Z_MIN_PIN P1_24 // Z+ #endif #else - #define Z_MIN_PIN P1_25 // Z- - #define Z_MAX_PIN P1_24 // Z+ + #define Z_MIN_PIN P1_25 // Z- + #define Z_MAX_PIN P1_24 // Z+ #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN P1_24 + #define Z_MIN_PROBE_PIN P1_24 #endif // // Steppers // -#define X_STEP_PIN P2_02 -#define X_DIR_PIN P2_03 -#define X_ENABLE_PIN P2_01 +#define X_STEP_PIN P2_02 +#define X_DIR_PIN P2_03 +#define X_ENABLE_PIN P2_01 #ifndef X_CS_PIN - #define X_CS_PIN P1_01 + #define X_CS_PIN P1_01 #endif -#define Y_STEP_PIN P0_19 -#define Y_DIR_PIN P0_20 -#define Y_ENABLE_PIN P2_08 +#define Y_STEP_PIN P0_19 +#define Y_DIR_PIN P0_20 +#define Y_ENABLE_PIN P2_08 #ifndef Y_CS_PIN - #define Y_CS_PIN P1_08 + #define Y_CS_PIN P1_08 #endif -#define Z_STEP_PIN P0_22 -#define Z_DIR_PIN P2_11 -#define Z_ENABLE_PIN P0_21 +#define Z_STEP_PIN P0_22 +#define Z_DIR_PIN P2_11 +#define Z_ENABLE_PIN P0_21 #ifndef Z_CS_PIN - #define Z_CS_PIN P1_10 + #define Z_CS_PIN P1_10 #endif -#define E0_STEP_PIN P2_13 -#define E0_DIR_PIN P0_11 -#define E0_ENABLE_PIN P2_12 +#define E0_STEP_PIN P2_13 +#define E0_DIR_PIN P0_11 +#define E0_ENABLE_PIN P2_12 #ifndef E0_CS_PIN - #define E0_CS_PIN P1_15 + #define E0_CS_PIN P1_15 #endif -#define E1_STEP_PIN P0_01 -#define E1_DIR_PIN P0_00 -#define E1_ENABLE_PIN P0_10 +#define E1_STEP_PIN P0_01 +#define E1_DIR_PIN P0_00 +#define E1_ENABLE_PIN P0_10 #ifndef E1_CS_PIN - #define E1_CS_PIN P1_17 + #define E1_CS_PIN P1_17 #endif // @@ -142,13 +142,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P4_28 + #define TMC_SW_MOSI P4_28 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 + #define TMC_SW_MISO P0_05 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 + #define TMC_SW_SCK P0_04 #endif #endif @@ -175,23 +175,23 @@ // Software serial // - #define X_SERIAL_TX_PIN P1_04 - #define X_SERIAL_RX_PIN P1_01 + #define X_SERIAL_TX_PIN P1_04 + #define X_SERIAL_RX_PIN P1_01 - #define Y_SERIAL_TX_PIN P1_09 - #define Y_SERIAL_RX_PIN P1_08 + #define Y_SERIAL_TX_PIN P1_09 + #define Y_SERIAL_RX_PIN P1_08 - #define Z_SERIAL_TX_PIN P1_14 - #define Z_SERIAL_RX_PIN P1_10 + #define Z_SERIAL_TX_PIN P1_14 + #define Z_SERIAL_RX_PIN P1_10 - #define E0_SERIAL_TX_PIN P1_16 - #define E0_SERIAL_RX_PIN P1_15 + #define E0_SERIAL_TX_PIN P1_16 + #define E0_SERIAL_RX_PIN P1_15 - #define E1_SERIAL_TX_PIN P4_29 - #define E1_SERIAL_RX_PIN P1_17 + #define E1_SERIAL_TX_PIN P4_29 + #define E1_SERIAL_RX_PIN P1_17 - #define Z2_SERIAL_TX_PIN P4_29 - #define Z2_SERIAL_RX_PIN P1_17 + #define Z2_SERIAL_TX_PIN P4_29 + #define Z2_SERIAL_RX_PIN P1_17 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -201,35 +201,35 @@ // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 // Analog Input A0 (TH1) -#define TEMP_BED_PIN P0_24_A1 // Analog Input A1 (TB) -#define TEMP_1_PIN P0_25_A2 // Analog Input A2 (TH2) +#define TEMP_0_PIN P0_23_A0 // Analog Input A0 (TH1) +#define TEMP_BED_PIN P0_24_A1 // Analog Input A1 (TB) +#define TEMP_1_PIN P0_25_A2 // Analog Input A2 (TH2) // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_0_PIN P2_07 +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 #if HOTENDS == 1 #ifndef FAN1_PIN - #define FAN1_PIN P2_06 + #define FAN1_PIN P2_06 #endif #else #ifndef HEATER_1_PIN - #define HEATER_1_PIN P2_06 + #define HEATER_1_PIN P2_06 #endif #endif #ifndef FAN_PIN - #define FAN_PIN P2_04 + #define FAN_PIN P2_04 #endif // // Misc. Functions // -#define LED_PIN P1_18 // Used as a status indicator -#define LED2_PIN P1_19 -#define LED3_PIN P1_20 -#define LED4_PIN P1_21 +#define LED_PIN P1_18 // Used as a status indicator +#define LED2_PIN P1_19 +#define LED3_PIN P1_20 +#define LED4_PIN P1_21 /** * _____ _____ @@ -242,83 +242,83 @@ * EXP1 EXP2 */ #if HAS_SPI_LCD - #define BEEPER_PIN P1_31 - #define BTN_ENC P1_30 + #define BEEPER_PIN P1_31 + #define BTN_ENC P1_30 #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS P1_00 + #define LCD_PINS_RS P1_00 - #define BTN_EN1 P0_18 - #define BTN_EN2 P0_15 + #define BTN_EN1 P0_18 + #define BTN_EN2 P0_15 - #define LCD_PINS_ENABLE P1_22 - #define LCD_PINS_D4 P0_17 + #define LCD_PINS_ENABLE P1_22 + #define LCD_PINS_D4 P0_17 #else - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 - #define LCD_SDSS P0_28 + #define LCD_SDSS P0_28 #if ENABLED(MKS_12864OLED_SSD1306) - #define LCD_PINS_DC P0_17 - #define DOGLCD_CS P0_16 - #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define LCD_PINS_DC P0_17 + #define DOGLCD_CS P0_16 + #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_SCK P0_15 + #define DOGLCD_MOSI P0_18 - #define LCD_PINS_RS P1_00 - #define LCD_PINS_D7 P1_22 - #define KILL_PIN -1 // NC + #define LCD_PINS_RS P1_00 + #define LCD_PINS_D7 P1_22 + #define KILL_PIN -1 // NC - #else // !MKS_12864OLED_SSD1306 + #else // !MKS_12864OLED_SSD1306 - #define LCD_PINS_RS P0_16 + #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS P0_18 - #define DOGLCD_A0 P0_16 - #define DOGLCD_SCK P0_07 - #define DOGLCD_MOSI P1_20 + #define DOGLCD_CS P0_18 + #define DOGLCD_A0 P0_16 + #define DOGLCD_SCK P0_07 + #define DOGLCD_MOSI P1_20 - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 - #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN P0_15 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN P0_15 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P0_17 + #define RGB_LED_R_PIN P0_17 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_00 + #define RGB_LED_G_PIN P1_00 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_22 + #define RGB_LED_B_PIN P1_22 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P0_17 + #define NEOPIXEL_PIN P0_17 #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS P0_17 - #define DOGLCD_A0 P1_00 + #define DOGLCD_CS P0_17 + #define DOGLCD_A0 P1_00 #endif #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 P0_17 - #define LCD_PINS_D6 P1_00 - #define LCD_PINS_D7 P1_22 + #define LCD_PINS_D5 P0_17 + #define LCD_PINS_D6 P1_00 + #define LCD_PINS_D7 P1_22 #endif #endif // !FYSETC_MINI_12864 @@ -330,20 +330,20 @@ #endif // HAS_SPI_LCD #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN P0_27 - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 + #define SD_DETECT_PIN P0_27 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 #if SD_CONNECTION_IS(ONBOARD) - #define SS_PIN ONBOARD_SD_CS_PIN + #define SS_PIN ONBOARD_SD_CS_PIN #else - #define SS_PIN P0_28 + #define SS_PIN P0_28 #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." @@ -352,6 +352,6 @@ // // Other Pins // -//#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) -//#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) -//#define PS_ON_PIN P1_23 // SERVO P1.23 +//#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +//#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +//#define PS_ON_PIN P1_23 // SERVO P1.23 diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 2303c1885c..b8b04a348c 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -51,58 +51,58 @@ // // Servos // -#define SERVO0_PIN P1_20 // (11) -#define SERVO1_PIN P1_21 // ( 6) also on J5-1 -#define SERVO2_PIN P1_19 // ( 5) -#define SERVO3_PIN P1_18 // ( 4) 5V output +#define SERVO0_PIN P1_20 // (11) +#define SERVO1_PIN P1_21 // ( 6) also on J5-1 +#define SERVO2_PIN P1_19 // ( 5) +#define SERVO3_PIN P1_18 // ( 4) 5V output // // Limit Switches // -#define X_MIN_PIN P1_24 // ( 3) 10k pullup to 3.3V, 1K series -#define X_MAX_PIN P1_25 // ( 2) 10k pullup to 3.3V, 1K series -#define Y_MIN_PIN P1_26 // (14) 10k pullup to 3.3V, 1K series -#define Y_MAX_PIN P1_27 // (15) 10k pullup to 3.3V, 1K series -#define Z_MIN_PIN P1_29 // (18) 10k pullup to 3.3V, 1K series -#define Z_MAX_PIN P1_28 // (19) 10k pullup to 3.3V, 1K series -#define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups +#define X_MIN_PIN P1_24 // ( 3) 10k pullup to 3.3V, 1K series +#define X_MAX_PIN P1_25 // ( 2) 10k pullup to 3.3V, 1K series +#define Y_MIN_PIN P1_26 // (14) 10k pullup to 3.3V, 1K series +#define Y_MAX_PIN P1_27 // (15) 10k pullup to 3.3V, 1K series +#define Z_MIN_PIN P1_29 // (18) 10k pullup to 3.3V, 1K series +#define Z_MAX_PIN P1_28 // (19) 10k pullup to 3.3V, 1K series +#define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups // // Steppers // -#define X_STEP_PIN P2_01 // (54) -#define X_DIR_PIN P0_11 // (55) -#define X_ENABLE_PIN P0_10 // (38) +#define X_STEP_PIN P2_01 // (54) +#define X_DIR_PIN P0_11 // (55) +#define X_ENABLE_PIN P0_10 // (38) #ifndef X_CS_PIN - #define X_CS_PIN P1_01 // ETH + #define X_CS_PIN P1_01 // ETH #endif -#define Y_STEP_PIN P2_02 // (60) -#define Y_DIR_PIN P0_20 // (61) -#define Y_ENABLE_PIN P0_19 // (56) +#define Y_STEP_PIN P2_02 // (60) +#define Y_DIR_PIN P0_20 // (61) +#define Y_ENABLE_PIN P0_19 // (56) #ifndef Y_CS_PIN - #define Y_CS_PIN P1_04 // ETH + #define Y_CS_PIN P1_04 // ETH #endif -#define Z_STEP_PIN P2_03 // (46) -#define Z_DIR_PIN P0_22 // (48) -#define Z_ENABLE_PIN P0_21 // (62) +#define Z_STEP_PIN P2_03 // (46) +#define Z_DIR_PIN P0_22 // (48) +#define Z_ENABLE_PIN P0_21 // (62) #ifndef Z_CS_PIN - #define Z_CS_PIN P1_10 // ETH + #define Z_CS_PIN P1_10 // ETH #endif -#define E0_STEP_PIN P2_00 // (26) -#define E0_DIR_PIN P0_05 // (28) -#define E0_ENABLE_PIN P0_04 // (24) +#define E0_STEP_PIN P2_00 // (26) +#define E0_DIR_PIN P0_05 // (28) +#define E0_ENABLE_PIN P0_04 // (24) #ifndef E0_CS_PIN - #define E0_CS_PIN P1_14 // ETH + #define E0_CS_PIN P1_14 // ETH #endif -#define E1_STEP_PIN P2_08 // (36) -#define E1_DIR_PIN P2_13 // (34) -#define E1_ENABLE_PIN P4_29 // (30) +#define E1_STEP_PIN P2_08 // (36) +#define E1_DIR_PIN P2_13 // (34) +#define E1_ENABLE_PIN P4_29 // (30) #ifndef E1_CS_PIN - #define E1_CS_PIN -1 + #define E1_CS_PIN -1 #endif // @@ -110,13 +110,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_00 // ETH + #define TMC_SW_MOSI P1_00 // ETH #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_08 // ETH + #define TMC_SW_MISO P1_08 // ETH #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_09 // ETH + #define TMC_SW_SCK P1_09 // ETH #endif #endif @@ -136,31 +136,31 @@ // P2_13 E1-Dir #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN P0_01 + #define X_SERIAL_TX_PIN P0_01 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN P0_01 + #define X_SERIAL_RX_PIN P0_01 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN P0_00 + #define Y_SERIAL_TX_PIN P0_00 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN P0_00 + #define Y_SERIAL_RX_PIN P0_00 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN P2_13 + #define Z_SERIAL_TX_PIN P2_13 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN P2_13 + #define Z_SERIAL_RX_PIN P2_13 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN P2_08 + #define E0_SERIAL_TX_PIN P2_08 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN P2_08 + #define E0_SERIAL_RX_PIN P2_08 #endif // Reduce baud rate to improve software serial reliability @@ -171,14 +171,14 @@ // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_0_PIN -#define TEMP_BED_PIN P0_24_A1 // A1 (T1) - (68) - TEMP_BED_PIN -#define TEMP_1_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_1_PIN -#define TEMP_2_PIN P0_26_A3 // A3 - (63) - J5-3 & AUX-2 -#define TEMP_3_PIN P1_30_A4 // A4 - (37) - BUZZER_PIN -//#define TEMP_4_PIN P1_31_A5 // A5 - (49) - SD_DETECT_PIN +#define TEMP_0_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_0_PIN +#define TEMP_BED_PIN P0_24_A1 // A1 (T1) - (68) - TEMP_BED_PIN +#define TEMP_1_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_1_PIN +#define TEMP_2_PIN P0_26_A3 // A3 - (63) - J5-3 & AUX-2 +#define TEMP_3_PIN P1_30_A4 // A4 - (37) - BUZZER_PIN +//#define TEMP_4_PIN P1_31_A5 // A5 - (49) - SD_DETECT_PIN //#define ?? P0_03_A6 // A6 - ( 0) - RXD0 - J4-4 & AUX-1 -#define FILWIDTH_PIN P0_02_A7 // A7 - ( 1) - TXD0 - J4-5 & AUX-1 +#define FILWIDTH_PIN P0_02_A7 // A7 - ( 1) - TXD0 - J4-5 & AUX-1 // // Augmentation for auto-assigning RAMPS plugs @@ -201,69 +201,69 @@ // Heaters / Fans // #ifndef MOSFET_D_PIN - #define MOSFET_D_PIN -1 + #define MOSFET_D_PIN -1 #endif #ifndef RAMPS_D8_PIN - #define RAMPS_D8_PIN P2_07 // (8) + #define RAMPS_D8_PIN P2_07 // (8) #endif #ifndef RAMPS_D9_PIN - #define RAMPS_D9_PIN P2_04 // (9) + #define RAMPS_D9_PIN P2_04 // (9) #endif #ifndef RAMPS_D10_PIN - #define RAMPS_D10_PIN P2_05 // (10) + #define RAMPS_D10_PIN P2_05 // (10) #endif -#define HEATER_0_PIN RAMPS_D10_PIN +#define HEATER_0_PIN RAMPS_D10_PIN -#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed - #define HEATER_BED_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan - #define HEATER_1_PIN RAMPS_D9_PIN -#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed - #define HEATER_1_PIN RAMPS_D9_PIN - #define HEATER_BED_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan - #define FAN1_PIN RAMPS_D8_PIN -#elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") - #define HEATER_BED_PIN RAMPS_D8_PIN +#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed + #define HEATER_BED_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan + #define HEATER_1_PIN RAMPS_D9_PIN +#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed + #define HEATER_1_PIN RAMPS_D9_PIN + #define HEATER_BED_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan + #define FAN1_PIN RAMPS_D8_PIN +#elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") + #define HEATER_BED_PIN RAMPS_D8_PIN #if HOTENDS == 1 - #define FAN1_PIN MOSFET_D_PIN + #define FAN1_PIN MOSFET_D_PIN #else - #define HEATER_1_PIN MOSFET_D_PIN + #define HEATER_1_PIN MOSFET_D_PIN #endif #endif #ifndef FAN_PIN #if EITHER(IS_RAMPS_EFB, IS_RAMPS_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN RAMPS_D9_PIN + #define FAN_PIN RAMPS_D9_PIN #elif EITHER(IS_RAMPS_EEF, IS_RAMPS_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN RAMPS_D8_PIN - #elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed - #define FAN_PIN P1_18 // (4) IO pin. Buffer needed - #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN RAMPS_D9_PIN + #define FAN_PIN RAMPS_D8_PIN + #elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed + #define FAN_PIN P1_18 // (4) IO pin. Buffer needed + #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") + #define FAN_PIN RAMPS_D9_PIN #endif #endif // // Misc. Functions // -#define LED_PIN P4_28 // (13) +#define LED_PIN P4_28 // (13) // define digital pin 5 for the filament runout sensor. Use the RAMPS 1.4 digital input 5 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN P1_19 // (5) + #define FIL_RUNOUT_PIN P1_19 // (5) #endif -#define PS_ON_PIN P2_12 // (12) +#define PS_ON_PIN P2_12 // (12) #if !defined(MAX6675_SS_PIN) && DISABLED(USE_ZMAX_PLUG) - #define MAX6675_SS_PIN P1_28 + #define MAX6675_SS_PIN P1_28 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN) - #if !defined(NUM_SERVOS) || NUM_SERVOS < 4 // Try to use servo connector - #define CASE_LIGHT_PIN P1_18 // (4) MUST BE HARDWARE PWM + #if !defined(NUM_SERVOS) || NUM_SERVOS < 4 // Try to use servo connector + #define CASE_LIGHT_PIN P1_18 // (4) MUST BE HARDWARE PWM #endif #endif @@ -279,19 +279,19 @@ #error "LASER_FEATURE requires 3 free servo pins." #endif #endif - #define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown! - #define SPINDLE_LASER_PWM_PIN SERVO3_PIN // (4) MUST BE HARDWARE PWM - #define SPINDLE_DIR_PIN SERVO2_PIN // (5) + #define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown! + #define SPINDLE_LASER_PWM_PIN SERVO3_PIN // (4) MUST BE HARDWARE PWM + #define SPINDLE_DIR_PIN SERVO2_PIN // (5) #endif // // Průša i3 MK2 Multiplexer Support // #if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0 - #define E_MUX0_PIN P0_03 // ( 0) Z_CS_PIN - #define E_MUX1_PIN P0_02 // ( 1) E0_CS_PIN + #define E_MUX0_PIN P0_03 // ( 0) Z_CS_PIN + #define E_MUX1_PIN P0_02 // ( 1) E0_CS_PIN #endif -#define E_MUX2_PIN P0_26 // (63) E1_CS_PIN +#define E_MUX2_PIN P0_26 // (63) E1_CS_PIN /** * LCD / Controller @@ -322,101 +322,101 @@ // 10-pin IDC connector trimmed or replaced with a 12-pin IDC connector to fit J3. // Requires REVERSE_ENCODER_DIRECTION in Configuration.h - #define BEEPER_PIN P2_11 // J3-3 & AUX-4 + #define BEEPER_PIN P2_11 // J3-3 & AUX-4 - #define BTN_EN1 P0_16 // J3-7 & AUX-4 - #define BTN_EN2 P1_23 // J3-5 & AUX-4 - #define BTN_ENC P3_25 // J3-4 & AUX-4 + #define BTN_EN1 P0_16 // J3-7 & AUX-4 + #define BTN_EN2 P1_23 // J3-5 & AUX-4 + #define BTN_ENC P3_25 // J3-4 & AUX-4 - #define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS) - #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) - #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) + #define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS) + #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) + #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) #elif HAS_SPI_LCD - //#define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 - //#define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 - //#define MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 - //#define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) + //#define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 + //#define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 + //#define MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 + //#define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) #if ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN P1_01 - #define BTN_ENC P1_04 + #define BEEPER_PIN P1_01 + #define BTN_ENC P1_04 #else - #define BEEPER_PIN P1_30 // (37) not 5V tolerant - #define BTN_ENC P2_11 // (35) J3-3 & AUX-4 + #define BEEPER_PIN P1_30 // (37) not 5V tolerant + #define BTN_ENC P2_11 // (35) J3-3 & AUX-4 #endif - #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 - #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 + #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 + #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 - #define SD_DETECT_PIN P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) - #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 - #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 - #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 + #define SD_DETECT_PIN P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) + #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 + #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 + #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 #if ENABLED(NEWPANEL) #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3 - #define SHIFT_LD P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) + #define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3 + #define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3 + #define SHIFT_LD P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) #endif #else - //#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4 - //#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4 - //#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4 - //#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4 + //#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4 + //#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4 + //#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4 + //#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4 #endif #if ANY(VIKI2, miniVIKI) // #define LCD_SCREEN_ROT_180 - #define DOGLCD_CS P0_16 // (16) - #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 - #define DOGLCD_SCK SCK_PIN - #define DOGLCD_MOSI MOSI_PIN + #define DOGLCD_CS P0_16 // (16) + #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 + #define DOGLCD_SCK SCK_PIN + #define DOGLCD_MOSI MOSI_PIN - #define STAT_LED_BLUE_PIN P0_26 //(63) may change if cable changes - #define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes + #define STAT_LED_BLUE_PIN P0_26 //(63) may change if cable changes + #define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes #else #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_SCK P0_15 + #define DOGLCD_MOSI P0_18 // EXP1 on LCD adapter is not usable - using Ethernet connector instead - #define DOGLCD_CS P1_09 - #define DOGLCD_A0 P1_14 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + #define DOGLCD_CS P1_09 + #define DOGLCD_A0 P1_14 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN P0_16 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN P0_16 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P1_00 + #define RGB_LED_R_PIN P1_00 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_01 + #define RGB_LED_G_PIN P1_01 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_08 + #define RGB_LED_B_PIN P1_08 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P1_00 + #define NEOPIXEL_PIN P1_00 #endif #else - #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 - #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 + #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 + #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 #endif - #define LCD_BACKLIGHT_PIN P0_16 //(16) J3-7 & AUX-4 - only used on DOGLCD controllers - #define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3 + #define LCD_BACKLIGHT_PIN P0_16 //(16) J3-7 & AUX-4 - only used on DOGLCD controllers + #define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3 + #define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 P1_17 // (71) ENET_MDIO - #define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER - #define LCD_PINS_D7 P1_10 // (75) ENET_RXD1 + #define LCD_PINS_D5 P1_17 // (71) ENET_MDIO + #define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER + #define LCD_PINS_D7 P1_10 // (75) ENET_RXD1 #endif #endif @@ -434,38 +434,38 @@ // Ethernet pins // #if DISABLED(ULTIPANEL) - #define ENET_MDIO P1_17 // (71) J12-4 - #define ENET_RX_ER P1_14 // (73) J12-6 - #define ENET_RXD1 P1_10 // (75) J12-8 + #define ENET_MDIO P1_17 // (71) J12-4 + #define ENET_RX_ER P1_14 // (73) J12-6 + #define ENET_RXD1 P1_10 // (75) J12-8 #endif -#define ENET_MOC P1_16 // (70) J12-3 -#define REF_CLK P1_15 // (72) J12-5 -#define ENET_RXD0 P1_09 // (74) J12-7 -#define ENET_CRS P1_08 // (76) J12-9 -#define ENET_TX_EN P1_04 // (77) J12-10 -#define ENET_TXD0 P1_00 // (78) J12-11 -#define ENET_TXD1 P1_01 // (79) J12-12 +#define ENET_MOC P1_16 // (70) J12-3 +#define REF_CLK P1_15 // (72) J12-5 +#define ENET_RXD0 P1_09 // (74) J12-7 +#define ENET_CRS P1_08 // (76) J12-9 +#define ENET_TX_EN P1_04 // (77) J12-10 +#define ENET_TXD0 P1_00 // (78) J12-11 +#define ENET_TXD1 P1_01 // (79) J12-12 // // SD Support // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 - #define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 - #define MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 - #define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin + #define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 + #define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 + #define MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 + #define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 3c55ac9be3..6f84f87bba 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -41,80 +41,79 @@ // // Servos // -#define SERVO0_PIN P1_23 +#define SERVO0_PIN P1_23 // // Limit Switches // -#define X_MIN_PIN P1_28 -#define X_MAX_PIN P1_25 -#define Y_MIN_PIN P2_11 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN P1_27 -#define Z_MAX_PIN -1 -#define Z_PROBE P1_22 +#define X_MIN_PIN P1_28 +#define X_MAX_PIN P1_25 +#define Y_MIN_PIN P2_11 +#define Y_MAX_PIN -1 +#define Z_MIN_PIN P1_27 +#define Z_MAX_PIN -1 +#define Z_PROBE P1_22 // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) -#define TEMP_0_PIN P0_24_A1 // A1 (TH2) -#define TEMP_1_PIN P0_25_A2 // A2 (TH3) - +#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) +#define TEMP_0_PIN P0_24_A1 // A1 (TH2) +#define TEMP_1_PIN P0_25_A2 // A2 (TH3) // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_BED2_PIN P2_04 -#define HEATER_0_PIN P2_07 -#define HEATER_1_PIN P2_06 +#define HEATER_BED_PIN P2_05 +#define HEATER_BED2_PIN P2_04 +#define HEATER_0_PIN P2_07 +#define HEATER_1_PIN P2_06 #ifndef FAN_PIN - #define FAN_PIN P1_24 + #define FAN_PIN P1_24 #endif -#define FAN1_PIN P1_26 +#define FAN1_PIN P1_26 // // Display // #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 - #define LCD_PINS_D5 P1_00 - #define LCD_PINS_D6 P1_01 - #define LCD_PINS_D7 P1_04 - #define BEEPER_PIN P1_31 + #define LCD_PINS_RS P0_16 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 + #define LCD_PINS_D5 P1_00 + #define LCD_PINS_D6 P1_01 + #define LCD_PINS_D7 P1_04 + #define BEEPER_PIN P1_31 - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 - #define BTN_ENC P1_30 + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #define BTN_ENC P1_30 - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #endif // REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index 1b91e4f50b..95cbd2163e 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -41,93 +41,92 @@ // // Servos // -#define SERVO0_PIN P1_23 +#define SERVO0_PIN P1_23 // // Limit Switches // -#define X_MIN_PIN P1_24 -#define X_MAX_PIN P1_27 -#define Y_MIN_PIN P1_25 -#define Y_MAX_PIN P1_28 -#define Z_MIN_PIN P1_26 -#define Z_MAX_PIN P1_29 +#define X_MIN_PIN P1_24 +#define X_MAX_PIN P1_27 +#define Y_MIN_PIN P1_25 +#define Y_MAX_PIN P1_28 +#define Z_MIN_PIN P1_26 +#define Z_MAX_PIN P1_29 // // Steppers // -#define X_STEP_PIN P2_01 -#define X_DIR_PIN P0_11 -#define X_ENABLE_PIN P0_10 +#define X_STEP_PIN P2_01 +#define X_DIR_PIN P0_11 +#define X_ENABLE_PIN P0_10 #ifndef X_CS_PIN - #define X_CS_PIN P0_10 // BSD2660 default + #define X_CS_PIN P0_10 // BSD2660 default #endif -#define Y_STEP_PIN P2_02 -#define Y_DIR_PIN P0_20 -#define Y_ENABLE_PIN P0_19 +#define Y_STEP_PIN P2_02 +#define Y_DIR_PIN P0_20 +#define Y_ENABLE_PIN P0_19 #ifndef Y_CS_PIN - #define Y_CS_PIN P0_19 // BSD2660 default + #define Y_CS_PIN P0_19 // BSD2660 default #endif -#define Z_STEP_PIN P2_03 -#define Z_DIR_PIN P0_22 -#define Z_ENABLE_PIN P0_21 +#define Z_STEP_PIN P2_03 +#define Z_DIR_PIN P0_22 +#define Z_ENABLE_PIN P0_21 #ifndef Z_CS_PIN - #define Z_CS_PIN P0_21 // BSD2660 default + #define Z_CS_PIN P0_21 // BSD2660 default #endif -#define E0_STEP_PIN P2_00 -#define E0_DIR_PIN P0_05 -#define E0_ENABLE_PIN P0_04 +#define E0_STEP_PIN P2_00 +#define E0_DIR_PIN P0_05 +#define E0_ENABLE_PIN P0_04 #ifndef E0_CS_PIN - #define E0_CS_PIN P0_04 // BSD2660 default + #define E0_CS_PIN P0_04 // BSD2660 default #endif -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 #ifndef E1_CS_PIN - #define E1_CS_PIN P4_29 // BSD2660 default + #define E1_CS_PIN P4_29 // BSD2660 default #endif // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) -#define TEMP_0_PIN P0_24_A1 // A1 (TH2) -#define TEMP_1_PIN P0_25_A2 // A2 (TH3) - +#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) +#define TEMP_0_PIN P0_24_A1 // A1 (TH2) +#define TEMP_1_PIN P0_25_A2 // A2 (TH3) // // Heaters / Fans // -#define HEATER_BED_PIN P2_07 -#define HEATER_0_PIN P2_04 -#define HEATER_1_PIN P2_05 +#define HEATER_BED_PIN P2_07 +#define HEATER_0_PIN P2_04 +#define HEATER_1_PIN P2_05 #ifndef FAN_PIN - #define FAN_PIN P0_26 + #define FAN_PIN P0_26 #endif -#define FAN1_PIN P1_22 +#define FAN1_PIN P1_22 // // Display // #if ANY(VIKI2, miniVIKI) - #define BEEPER_PIN P1_31 - #define DOGLCD_A0 P2_06 - #define DOGLCD_CS P0_16 + #define BEEPER_PIN P1_31 + #define DOGLCD_A0 P2_06 + #define DOGLCD_CS P0_16 - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 - #define BTN_ENC P2_11 + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #define BTN_ENC P2_11 - #define SD_DETECT_PIN P1_18 - #define SDSS P1_21 + #define SD_DETECT_PIN P1_18 + #define SDSS P1_21 - #define STAT_LED_RED_PIN P1_19 - #define STAT_LED_BLUE_PIN P1_20 + #define STAT_LED_RED_PIN P1_19 + #define STAT_LED_BLUE_PIN P1_20 #endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index 7559d6ad50..ba1351e6f4 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -37,74 +37,74 @@ // // LED // -#define LED_PIN P1_18 +#define LED_PIN P1_18 // // Servos // -#define SERVO0_PIN P1_29 +#define SERVO0_PIN P1_29 // // Limit Switches // -#define X_STOP_PIN P1_24 -#define Y_STOP_PIN P1_26 -#define Z_STOP_PIN P1_28 +#define X_STOP_PIN P1_24 +#define Y_STOP_PIN P1_26 +#define Z_STOP_PIN P1_28 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN P2_04 + #define FIL_RUNOUT_PIN P2_04 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN P0_25_A2 // Analog Input (P0_25) + #define FILWIDTH_PIN P0_25_A2 // Analog Input (P0_25) #endif // // Steppers // -#define X_STEP_PIN P2_01 -#define X_DIR_PIN P0_11 -#define X_ENABLE_PIN P0_10 +#define X_STEP_PIN P2_01 +#define X_DIR_PIN P0_11 +#define X_ENABLE_PIN P0_10 -#define Y_STEP_PIN P2_02 -#define Y_DIR_PIN P0_20 -#define Y_ENABLE_PIN P0_19 +#define Y_STEP_PIN P2_02 +#define Y_DIR_PIN P0_20 +#define Y_ENABLE_PIN P0_19 -#define Z_STEP_PIN P2_03 -#define Z_DIR_PIN P0_22 -#define Z_ENABLE_PIN P0_21 +#define Z_STEP_PIN P2_03 +#define Z_DIR_PIN P0_22 +#define Z_ENABLE_PIN P0_21 -#define E0_STEP_PIN P2_00 -#define E0_DIR_PIN P0_05 -#define E0_ENABLE_PIN P0_04 +#define E0_STEP_PIN P2_00 +#define E0_DIR_PIN P0_05 +#define E0_ENABLE_PIN P0_04 // // DIGIPOT slave addresses // #ifndef DIGIPOT_I2C_ADDRESS_A - #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT + #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT #endif #ifndef DIGIPOT_I2C_ADDRESS_B - #define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT + #define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT #endif // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) -#define TEMP_0_PIN P0_24_A1 // A1 (TH2) +#define TEMP_BED_PIN P0_23_A0 // A0 (TH1) +#define TEMP_0_PIN P0_24_A1 // A1 (TH2) // // Heaters / Fans // -#define HEATER_BED_PIN P2_07 -#define HEATER_0_PIN P2_05 +#define HEATER_BED_PIN P2_07 +#define HEATER_0_PIN P2_05 #ifndef FAN_PIN - #define FAN_PIN P0_26 + #define FAN_PIN P0_26 #endif -#define FAN1_PIN P1_25 +#define FAN1_PIN P1_25 // // Display @@ -118,61 +118,61 @@ // 10-pin IDC connector trimmed or replaced with a 12-pin IDC connector to fit J3. // Requires REVERSE_ENCODER_DIRECTION in Configuration.h - #define BEEPER_PIN P2_11 // J3-3 & AUX-4 + #define BEEPER_PIN P2_11 // J3-3 & AUX-4 - #define BTN_EN1 P0_16 // J3-7 & AUX-4 - #define BTN_EN2 P1_23 // J3-5 & AUX-4 - #define BTN_ENC P3_25 // J3-4 & AUX-4 + #define BTN_EN1 P0_16 // J3-7 & AUX-4 + #define BTN_EN2 P1_23 // J3-5 & AUX-4 + #define BTN_ENC P3_25 // J3-4 & AUX-4 - #define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS) - #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) - #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) + #define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS) + #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) + #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) #else - #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 - #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 - #define BTN_ENC P2_11 // (35) J3-3 & AUX-4 + #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 + #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 + #define BTN_ENC P2_11 // (35) J3-3 & AUX-4 - #define SD_DETECT_PIN P1_31 // (49) not 5V tolerant J3-1 & AUX-3 - #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 - #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 - #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 - #define LCD_BACKLIGHT_PIN P0_16 // (16) J3-7 & AUX-4 - only used on DOGLCD controllers - #define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3 + #define SD_DETECT_PIN P1_31 // (49) not 5V tolerant J3-1 & AUX-3 + #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 + #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 + #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 + #define LCD_BACKLIGHT_PIN P0_16 // (16) J3-7 & AUX-4 - only used on DOGLCD controllers + #define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3 + #define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3 - #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 + #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3 - #define SHIFT_LD P1_31 // (49) not 5V tolerant J3-1 & AUX-3 + #define SHIFT_OUT P0_18 // (51) (MOSI) J3-10 & AUX-3 + #define SHIFT_CLK P0_15 // (52) (SCK) J3-9 & AUX-3 + #define SHIFT_LD P1_31 // (49) not 5V tolerant J3-1 & AUX-3 #elif DISABLED(NEWPANEL) - //#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4 - //#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4 - //#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4 - //#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4 + //#define SHIFT_OUT P2_11 // (35) J3-3 & AUX-4 + //#define SHIFT_CLK P3_26 // (31) J3-2 & AUX-4 + //#define SHIFT_LD P3_25 // (33) J3-4 & AUX-4 + //#define SHIFT_EN P1_22 // (41) J5-4 & AUX-4 #endif #if ANY(VIKI2, miniVIKI) //#define LCD_SCREEN_ROT_180 - #define BEEPER_PIN P1_30 // (37) may change if cable changes - #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 - #define DOGLCD_SCK SCK_PIN - #define DOGLCD_MOSI MOSI_PIN + #define BEEPER_PIN P1_30 // (37) may change if cable changes + #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 + #define DOGLCD_SCK SCK_PIN + #define DOGLCD_MOSI MOSI_PIN - #define STAT_LED_BLUE_PIN P0_26 // (63) may change if cable changes - #define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes + #define STAT_LED_BLUE_PIN P0_26 // (63) may change if cable changes + #define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes #else #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 P1_17 // (71) ENET_MDIO - #define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER - #define LCD_PINS_D7 P1_10 // (75) ENET_RXD1 + #define LCD_PINS_D5 P1_17 // (71) ENET_MDIO + #define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER + #define LCD_PINS_D7 P1_10 // (75) ENET_RXD1 #endif - #define BEEPER_PIN P1_30 // (37) not 5V tolerant - #define DOGLCD_CS P0_16 // (16) + #define BEEPER_PIN P1_30 // (37) not 5V tolerant + #define DOGLCD_CS P0_16 // (16) #endif #if ENABLED(MINIPANEL) @@ -199,22 +199,22 @@ // SD Support // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - #define SS_PIN P1_23 + #define SCK_PIN P0_15 + #define MISO_PIN P0_17 + #define MOSI_PIN P0_18 + #define SS_PIN P1_23 #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index 3556ff83f0..87d3cb459c 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -40,53 +40,53 @@ // // Servos // -#define SERVO0_PIN P1_23 +#define SERVO0_PIN P1_23 // // Limit Switches // -#define X_MIN_PIN P1_24 // 10k pullup to 3.3V -#define X_MAX_PIN P1_25 // 10k pullup to 3.3V -#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V -#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V -#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V -#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V +#define X_MIN_PIN P1_24 // 10k pullup to 3.3V +#define X_MAX_PIN P1_25 // 10k pullup to 3.3V +#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V +#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V +#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V +#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 -#define X_CS_PIN P1_10 // Ethernet Expansion - Pin 9 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 +#define X_CS_PIN P1_10 // Ethernet Expansion - Pin 9 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 -#define Y_CS_PIN P1_09 // Ethernet Expansion - Pin 10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 +#define Y_CS_PIN P1_09 // Ethernet Expansion - Pin 10 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 -#define Z_CS_PIN P1_00 // Ethernet Expansion - Pin 11 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 +#define Z_CS_PIN P1_00 // Ethernet Expansion - Pin 11 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 -#define E0_CS_PIN P1_04 // Ethernet Expansion - Pin 12 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 +#define E0_CS_PIN P1_04 // Ethernet Expansion - Pin 12 // // Default pins for TMC software SPI // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 + #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 + #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 + #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 #endif #endif @@ -94,42 +94,42 @@ // Analog Inputs // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 // P0_23 -#define TEMP_BED_PIN P0_24_A1 // P0_24 +#define TEMP_0_PIN P0_23_A0 // P0_23 +#define TEMP_BED_PIN P0_24_A1 // P0_24 // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_0_PIN P2_07 // FET 1 +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 // FET 1 #ifndef FAN_PIN - #define FAN_PIN P2_06 // FET 3 + #define FAN_PIN P2_06 // FET 3 #endif // // Auto fans // -#define AUTO_FAN_PIN P2_04 // FET 4 +#define AUTO_FAN_PIN P2_04 // FET 4 -#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN // // Misc. Functions // -#define LED_PIN P4_28 // Play LED +#define LED_PIN P4_28 // Play LED // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER #undef HEATER_0_PIN - #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 + #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 #undef HEATER_BED_PIN - #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET + #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET #undef FAN_PIN - #define SPINDLE_DIR_PIN P2_06 // FET 3 + #define SPINDLE_DIR_PIN P2_06 // FET 3 #endif // @@ -144,18 +144,18 @@ // #if HAS_SPI_LCD - #define BEEPER_PIN P0_27 // EXP2-7 - open drain + #define BEEPER_PIN P0_27 // EXP2-7 - open drain - #define BTN_EN1 P3_26 // EXP2-5 - #define BTN_EN2 P3_25 // EXP2-3 - #define BTN_ENC P1_30 // EXP1-2 + #define BTN_EN1 P3_26 // EXP2-5 + #define BTN_EN2 P3_25 // EXP2-3 + #define BTN_ENC P1_30 // EXP1-2 - #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_SDSS P0_28 // EXP2-4 - #define LCD_PINS_ENABLE P0_18 // EXP1-3 - #define LCD_PINS_D4 P0_15 // EXP1-5 + #define LCD_PINS_RS P0_16 // EXP1-4 + #define LCD_SDSS P0_28 // EXP2-4 + #define LCD_PINS_ENABLE P0_18 // EXP1-3 + #define LCD_PINS_D4 P0_15 // EXP1-5 - #define KILL_PIN P2_11 // EXP2-10 + #define KILL_PIN P2_11 // EXP2-10 #if ENABLED(SDSUPPORT) #error "SDSUPPORT is not currently supported by the Cohesion3D boards" @@ -166,13 +166,13 @@ // // Ethernet pins // -#define ENET_MDIO P1_17 -#define ENET_RX_ER P1_14 -#define ENET_RXD1 P1_10 -#define ENET_MOC P1_16 -#define REF_CLK P1_15 -#define ENET_RXD0 P1_09 -#define ENET_CRS P1_08 -#define ENET_TX_EN P1_04 -#define ENET_TXD0 P1_00 -#define ENET_TXD1 P1_01 +#define ENET_MDIO P1_17 +#define ENET_RX_ER P1_14 +#define ENET_RXD1 P1_10 +#define ENET_MOC P1_16 +#define REF_CLK P1_15 +#define ENET_RXD0 P1_09 +#define ENET_CRS P1_08 +#define ENET_TX_EN P1_04 +#define ENET_TXD0 P1_00 +#define ENET_TXD1 P1_01 diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 2502c76580..fa55a8adae 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -40,70 +40,70 @@ // // Servos // -#define SERVO0_PIN P2_04 +#define SERVO0_PIN P2_04 // // Limit Switches // -#define X_MIN_PIN P1_24 // 10k pullup to 3.3V -#define X_MAX_PIN P1_25 // 10k pullup to 3.3V -#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V -#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V -#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V -#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V +#define X_MIN_PIN P1_24 // 10k pullup to 3.3V +#define X_MAX_PIN P1_25 // 10k pullup to 3.3V +#define Y_MIN_PIN P1_26 // 10k pullup to 3.3V +#define Y_MAX_PIN P1_27 // 10k pullup to 3.3V +#define Z_MIN_PIN P1_28 // 10k pullup to 3.3V +#define Z_MAX_PIN P1_29 // 10k pullup to 3.3V // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN P1_29 + #define Z_MIN_PROBE_PIN P1_29 #endif // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 -#define X_CS_PIN P1_10 // Ethernet Expansion - Pin 9 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 +#define X_CS_PIN P1_10 // Ethernet Expansion - Pin 9 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 -#define Y_CS_PIN P1_09 // Ethernet Expansion - Pin 10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 +#define Y_CS_PIN P1_09 // Ethernet Expansion - Pin 10 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 -#define Z_CS_PIN P1_00 // Ethernet Expansion - Pin 11 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 +#define Z_CS_PIN P1_00 // Ethernet Expansion - Pin 11 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 -#define E0_CS_PIN P1_04 // Ethernet Expansion - Pin 12 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 +#define E0_CS_PIN P1_04 // Ethernet Expansion - Pin 12 -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 -#define E1_CS_PIN P1_01 // Ethernet Expansion - Pin 14 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 +#define E1_CS_PIN P1_01 // Ethernet Expansion - Pin 14 -#define E2_STEP_PIN P1_20 -#define E2_DIR_PIN P1_19 -#define E2_ENABLE_PIN P1_21 -#define E2_CS_PIN P1_18 // FET 6 +#define E2_STEP_PIN P1_20 +#define E2_DIR_PIN P1_19 +#define E2_ENABLE_PIN P1_21 +#define E2_CS_PIN P1_18 // FET 6 // // Default pins for TMC software SPI // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 + #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 + #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 + #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 #endif #endif @@ -111,42 +111,42 @@ // Analog Inputs // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 -#define TEMP_BED_PIN P0_24_A1 -#define TEMP_1_PIN P0_25_A2 +#define TEMP_0_PIN P0_23_A0 +#define TEMP_BED_PIN P0_24_A1 +#define TEMP_1_PIN P0_25_A2 #if ENABLED(FILAMENT_WIDTH_SENSOR) - #define FILWIDTH_PIN P0_26_A3 + #define FILWIDTH_PIN P0_26_A3 #else - #define TEMP_2_PIN P0_26_A3 + #define TEMP_2_PIN P0_26_A3 #endif // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_0_PIN P2_07 // FET 1 -#define HEATER_1_PIN P1_23 // FET 2 -#define HEATER_2_PIN P1_22 // FET 3 +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 // FET 1 +#define HEATER_1_PIN P1_23 // FET 2 +#define HEATER_2_PIN P1_22 // FET 3 #ifndef FAN_PIN - #define FAN_PIN P2_06 // FET 4 + #define FAN_PIN P2_06 // FET 4 #endif // // Auto fans // #if HOTENDS == 3 - #define AUTO_FAN_PIN P1_18 // FET 6 + #define AUTO_FAN_PIN P1_18 // FET 6 #else - #define AUTO_FAN_PIN P1_22 // FET 3 + #define AUTO_FAN_PIN P1_22 // FET 3 #endif -#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN // // Misc. Functions // -#define LED_PIN P4_28 // Play LED +#define LED_PIN P4_28 // Play LED // // M3/M4/M5 - Spindle/Laser Control @@ -155,9 +155,9 @@ #undef HEATER_0_PIN #undef HEATER_BED_PIN #undef FAN_PIN - #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 - #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET - #define SPINDLE_DIR_PIN P2_06 // FET 4 + #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 + #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET + #define SPINDLE_DIR_PIN P2_06 // FET 4 #endif // @@ -173,54 +173,54 @@ #if ENABLED(FYSETC_MINI_12864) - #define FORCE_SOFT_SPI // REQUIRED - results in LCD soft SPI mode 3 + #define FORCE_SOFT_SPI // REQUIRED - results in LCD soft SPI mode 3 - #define BEEPER_PIN P1_31 // EXP1-1 - #define BTN_ENC P1_30 // EXP1-2 - #define DOGLCD_CS P0_18 // EXP1-3 - #define DOGLCD_A0 P0_16 // EXP1-4 - #define LCD_RESET_PIN P0_15 // EXP1-5 + #define BEEPER_PIN P1_31 // EXP1-1 + #define BTN_ENC P1_30 // EXP1-2 + #define DOGLCD_CS P0_18 // EXP1-3 + #define DOGLCD_A0 P0_16 // EXP1-4 + #define LCD_RESET_PIN P0_15 // EXP1-5 // A custom cable is REQUIRED for EXP2 cable because the SCK & MOSI on the card's EXP2 are dedicated // to the onboard SD card. All required EXP2 signals come from the Ethernet connector. Pin 1 of this // connector is the one nearest the motor power connector. - #define DOGLCD_SCK P1_17 // EXP2-2 => Ethernet pin 5 (bottom, 3 from left) - #define BTN_EN2 P1_09 // EXP2-3 => Ethernet pin 9 (bottom, 5 from left) - #define BTN_EN1 P1_04 // EXP2-5 => Ethernet pin 11 (bottom, 6 from left) - #define DOGLCD_MOSI P1_01 // EXP2-6 => Ethernet pin 13 (bottom, 7 from left) + #define DOGLCD_SCK P1_17 // EXP2-2 => Ethernet pin 5 (bottom, 3 from left) + #define BTN_EN2 P1_09 // EXP2-3 => Ethernet pin 9 (bottom, 5 from left) + #define BTN_EN1 P1_04 // EXP2-5 => Ethernet pin 11 (bottom, 6 from left) + #define DOGLCD_MOSI P1_01 // EXP2-6 => Ethernet pin 13 (bottom, 7 from left) // A custom EXP1 cable is required colored LEDs. Pins 1-5, 9, 10 of the cable go to pins 1-5, 9, 10 // on the board's EXP1 connector. Pins 6, 7, and 8 of the EXP1 cable go to the Ethernet connector. // Rev 1.2 displays do NOT require the RGB LEDs. 2.0 and 2.1 displays do require RGB. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) + #define RGB_LED_R_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_10 // EXP1-7 => Ethernet pin 10 (top row, 5 from left) + #define RGB_LED_G_PIN P1_10 // EXP1-7 => Ethernet pin 10 (top row, 5 from left) #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_00 // EXP1-8 => Ethernet pin 12 (top row, 6 from left) + #define RGB_LED_B_PIN P1_00 // EXP1-8 => Ethernet pin 12 (top row, 6 from left) #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) + #define NEOPIXEL_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) #endif #elif HAS_SPI_LCD - #define BEEPER_PIN P1_31 // EXP1-1 - //#define SD_DETECT_PIN P0_27 // EXP2-7 + #define BEEPER_PIN P1_31 // EXP1-1 + //#define SD_DETECT_PIN P0_27 // EXP2-7 - #define BTN_EN1 P3_26 // EXP2-5 - #define BTN_EN2 P3_25 // EXP2-3 - #define BTN_ENC P1_30 // EXP1-2 + #define BTN_EN1 P3_26 // EXP2-5 + #define BTN_EN2 P3_25 // EXP2-3 + #define BTN_ENC P1_30 // EXP1-2 - #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_SDSS P0_28 // EXP2-4 - #define LCD_PINS_ENABLE P0_18 // EXP1-3 - #define LCD_PINS_D4 P0_15 // EXP1-5 + #define LCD_PINS_RS P0_16 // EXP1-4 + #define LCD_SDSS P0_28 // EXP2-4 + #define LCD_PINS_ENABLE P0_18 // EXP1-3 + #define LCD_PINS_D4 P0_15 // EXP1-5 - #define KILL_PIN P2_11 // EXP2-10 + #define KILL_PIN P2_11 // EXP2-10 #endif // HAS_SPI_LCD @@ -228,22 +228,22 @@ // SD Support // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) - #define SCK_PIN P0_07 // (52) system defined J3-9 & AUX-3 - #define MISO_PIN P0_08 // (50) system defined J3-10 & AUX-3 - #define MOSI_PIN P0_09 // (51) system defined J3-10 & AUX-3 - #define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin + #define SCK_PIN P0_07 // (52) system defined J3-9 & AUX-3 + #define MISO_PIN P0_08 // (50) system defined J3-10 & AUX-3 + #define MOSI_PIN P0_09 // (51) system defined J3-10 & AUX-3 + #define SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN - #define SCK_PIN P0_07 - #define MISO_PIN P0_08 - #define MOSI_PIN P0_09 - #define SS_PIN ONBOARD_SD_CS_PIN + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif @@ -251,16 +251,16 @@ // // Ethernet pins // -//#define ENET_MDIO P1_17 // Ethernet pin 5 (bottom, 3 from left) -//#define ENET_RX_ER P1_14 -//#define ENET_RXD1 P1_10 // Ethernet pin 10 (top row, 5 from left) -//#define ENET_MOC P1_16 // Ethernet pin 6 (top row, 3 from left) -//#define REF_CLK P1_15 -//#define ENET_RXD0 P1_09 // Ethernet pin 9 (bottom, 5 from left) -//#define ENET_CRS P1_08 // Ethernet pin 8 (top row, 4 from left) - INPUT ONLY -//#define ENET_TX_EN P1_04 // Ethernet pin 11 (bottom, 6 from left) -//#define ENET_TXD0 P1_00 // Ethernet pin 12 (top row, 6 from left) -//#define ENET_TXD1 P1_01 // Ethernet pin 13 (bottom, 7 from left) +//#define ENET_MDIO P1_17 // Ethernet pin 5 (bottom, 3 from left) +//#define ENET_RX_ER P1_14 +//#define ENET_RXD1 P1_10 // Ethernet pin 10 (top row, 5 from left) +//#define ENET_MOC P1_16 // Ethernet pin 6 (top row, 3 from left) +//#define REF_CLK P1_15 +//#define ENET_RXD0 P1_09 // Ethernet pin 9 (bottom, 5 from left) +//#define ENET_CRS P1_08 // Ethernet pin 8 (top row, 4 from left) - INPUT ONLY +//#define ENET_TX_EN P1_04 // Ethernet pin 11 (bottom, 6 from left) +//#define ENET_TXD0 P1_00 // Ethernet pin 12 (top row, 6 from left) +//#define ENET_TXD1 P1_01 // Ethernet pin 13 (bottom, 7 from left) /** * EXP1 pins diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index 7a6d283fb4..fd98b5ef13 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -47,8 +47,8 @@ //#undef BTN_EN1 //#undef BTN_EN2 -//#define BTN_EN1 P1_23 // EXP2.5 -//#define BTN_EN2 P1_22 // EXP2.3 +//#define BTN_EN1 P1_23 // EXP2.5 +//#define BTN_EN2 P1_22 // EXP2.3 #if HAS_TMC_UART /** @@ -58,16 +58,16 @@ * In the worst case you may have to give up the LCD. * RX pins must be interrupt-capable. */ - #define X_SERIAL_TX_PIN P4_29 // J8-2 - #define X_SERIAL_RX_PIN P4_29 // J8-2 + #define X_SERIAL_TX_PIN P4_29 // J8-2 + #define X_SERIAL_RX_PIN P4_29 // J8-2 - #define Y_SERIAL_TX_PIN P2_08 // J8-3 - #define Y_SERIAL_RX_PIN P2_08 // J8-3 + #define Y_SERIAL_TX_PIN P2_08 // J8-3 + #define Y_SERIAL_RX_PIN P2_08 // J8-3 - #define Z_SERIAL_TX_PIN P2_11 // J8-4 - #define Z_SERIAL_RX_PIN P2_11 // J8-4 - #define E0_SERIAL_TX_PIN P2_13 // J8-5 - #define E0_SERIAL_RX_PIN P2_13 // J8-5 + #define Z_SERIAL_TX_PIN P2_11 // J8-4 + #define Z_SERIAL_RX_PIN P2_11 // J8-4 + #define E0_SERIAL_TX_PIN P2_13 // J8-5 + #define E0_SERIAL_RX_PIN P2_13 // J8-5 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index 3db8a99403..43db07ea5e 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -41,79 +41,79 @@ // // Servos // -#define SERVO0_PIN P1_23 +#define SERVO0_PIN P1_23 // // Limit Switches // -#define X_MIN_PIN P1_24 -#define X_MAX_PIN P1_25 -#define Y_MIN_PIN P1_26 -#define Y_MAX_PIN P1_27 -#define Z_MIN_PIN P1_28 -#define Z_MAX_PIN P1_29 +#define X_MIN_PIN P1_24 +#define X_MAX_PIN P1_25 +#define Y_MIN_PIN P1_26 +#define Y_MAX_PIN P1_27 +#define Z_MIN_PIN P1_28 +#define Z_MAX_PIN P1_29 // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P0_05 -#define X_ENABLE_PIN P0_04 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P0_05 +#define X_ENABLE_PIN P0_04 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P0_11 -#define Y_ENABLE_PIN P0_10 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P0_11 +#define Y_ENABLE_PIN P0_10 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P0_20 -#define Z_ENABLE_PIN P0_19 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P0_20 +#define Z_ENABLE_PIN P0_19 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P0_22 -#define E0_ENABLE_PIN P0_21 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P0_22 +#define E0_ENABLE_PIN P0_21 -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 // // Temperature Sensors // 3.3V max when defined as an analog input // -#define TEMP_0_PIN P0_23_A0 // (T1) -#define TEMP_BED_PIN P0_24_A1 // (T2) -#define TEMP_1_PIN P0_25_A2 // (T3) -#define TEMP_2_PIN P0_26_A3 // (T4) +#define TEMP_0_PIN P0_23_A0 // (T1) +#define TEMP_BED_PIN P0_24_A1 // (T2) +#define TEMP_1_PIN P0_25_A2 // (T3) +#define TEMP_2_PIN P0_26_A3 // (T4) // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_0_PIN P2_07 -#define HEATER_1_PIN P1_23 +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 +#define HEATER_1_PIN P1_23 #ifndef FAN_PIN - #define FAN_PIN P2_06 + #define FAN_PIN P2_06 #endif -#define FAN1_PIN P2_04 +#define FAN1_PIN P2_04 // // LCD / Controller // #if ANY(VIKI2, miniVIKI) - #define BEEPER_PIN P1_31 - #define DOGLCD_A0 P2_11 - #define DOGLCD_CS P0_16 + #define BEEPER_PIN P1_31 + #define DOGLCD_A0 P2_11 + #define DOGLCD_CS P0_16 - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 - #define BTN_ENC P1_30 + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #define BTN_ENC P1_30 - #define SD_DETECT_PIN P1_18 - #define SDSS P1_21 + #define SD_DETECT_PIN P1_18 + #define SDSS P1_21 - #define STAT_LED_RED_PIN P1_19 - #define STAT_LED_BLUE_PIN P1_20 + #define STAT_LED_RED_PIN P1_19 + #define STAT_LED_BLUE_PIN P1_20 #elif HAS_SPI_LCD diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 9f28c2d94e..d4030ed790 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -41,58 +41,58 @@ // // Servos // -#define SERVO0_PIN P2_04 +#define SERVO0_PIN P2_04 // // Limit Switches // -#define X_STOP_PIN P1_24 -#define Y_STOP_PIN P1_25 -#define Z_STOP_PIN P1_26 +#define X_STOP_PIN P1_24 +#define Y_STOP_PIN P1_25 +#define Z_STOP_PIN P1_26 // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN P1_27 + #define FIL_RUNOUT_PIN P1_27 #endif // // Steppers // -#define X_STEP_PIN P2_00 -#define X_DIR_PIN P1_16 -#define X_ENABLE_PIN P1_17 +#define X_STEP_PIN P2_00 +#define X_DIR_PIN P1_16 +#define X_ENABLE_PIN P1_17 -#define Y_STEP_PIN P2_01 -#define Y_DIR_PIN P1_10 -#define Y_ENABLE_PIN P1_09 +#define Y_STEP_PIN P2_01 +#define Y_DIR_PIN P1_10 +#define Y_ENABLE_PIN P1_09 -#define Z_STEP_PIN P2_02 -#define Z_DIR_PIN P1_15 -#define Z_ENABLE_PIN P1_14 +#define Z_STEP_PIN P2_02 +#define Z_DIR_PIN P1_15 +#define Z_ENABLE_PIN P1_14 -#define E0_STEP_PIN P2_03 -#define E0_DIR_PIN P1_04 -#define E0_ENABLE_PIN P1_08 +#define E0_STEP_PIN P2_03 +#define E0_DIR_PIN P1_04 +#define E0_ENABLE_PIN P1_08 -#define E1_STEP_PIN P2_08 -#define E1_DIR_PIN P2_13 -#define E1_ENABLE_PIN P4_29 +#define E1_STEP_PIN P2_08 +#define E1_DIR_PIN P2_13 +#define E1_ENABLE_PIN P4_29 #if HAS_TMC_UART // // TMC220x stepper drivers // Software serial // - #define X_SERIAL_TX_PIN P0_04 - #define X_SERIAL_RX_PIN P0_05 - #define Y_SERIAL_TX_PIN P0_10 - #define Y_SERIAL_RX_PIN P0_11 - #define Z_SERIAL_TX_PIN P0_19 - #define Z_SERIAL_RX_PIN P0_20 - #define E0_SERIAL_TX_PIN P0_22 - #define E0_SERIAL_RX_PIN P0_21 + #define X_SERIAL_TX_PIN P0_04 + #define X_SERIAL_RX_PIN P0_05 + #define Y_SERIAL_TX_PIN P0_10 + #define Y_SERIAL_RX_PIN P0_11 + #define Z_SERIAL_TX_PIN P0_19 + #define Z_SERIAL_RX_PIN P0_20 + #define E0_SERIAL_TX_PIN P0_22 + #define E0_SERIAL_RX_PIN P0_21 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -102,50 +102,50 @@ // Temp Sensors // 3.3V max when defined as an Analog Input! // -#if TEMP_SENSOR_0 == 20 // PT100 Adapter - #define TEMP_0_PIN P0_02_A7 // Analog Input +#if TEMP_SENSOR_0 == 20 // PT100 Adapter + #define TEMP_0_PIN P0_02_A7 // Analog Input #else - #define TEMP_0_PIN P0_23_A0 // Analog Input P0_23 + #define TEMP_0_PIN P0_23_A0 // Analog Input P0_23 #endif -#define TEMP_BED_PIN P0_24_A1 // Analog Input P0_24 -#define TEMP_1_PIN P0_25_A2 // Analog Input P0_25 +#define TEMP_BED_PIN P0_24_A1 // Analog Input P0_24 +#define TEMP_1_PIN P0_25_A2 // Analog Input P0_25 #if ENABLED(FILAMENT_WIDTH_SENSOR) - #define FILWIDTH_PIN P0_26_A3 // Analog Input P0_26 + #define FILWIDTH_PIN P0_26_A3 // Analog Input P0_26 #else - #define TEMP_2_PIN P0_26_A3 // Analog Input P0_26 + #define TEMP_2_PIN P0_26_A3 // Analog Input P0_26 #endif // // Heaters / Fans // -#define HEATER_BED_PIN P2_05 -#define HEATER_0_PIN P2_07 +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 #ifndef FAN_PIN - #define FAN_PIN P2_06 + #define FAN_PIN P2_06 #endif -#define FAN1_PIN P1_22 +#define FAN1_PIN P1_22 // // Auto fans // -#define AUTO_FAN_PIN P1_22 // FET 3 -#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN +#define AUTO_FAN_PIN P1_22 // FET 3 +#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN +#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN // // SD Card // -#define SDCARD_CONNECTION ONBOARD +#define SDCARD_CONNECTION ONBOARD -#define SCK_PIN P0_07 -#define MISO_PIN P0_08 -#define MOSI_PIN P0_09 -#define ONBOARD_SD_CS_PIN P0_06 -#define SS_PIN ONBOARD_SD_CS_PIN +#define SCK_PIN P0_07 +#define MISO_PIN P0_08 +#define MOSI_PIN P0_09 +#define ONBOARD_SD_CS_PIN P0_06 +#define SS_PIN ONBOARD_SD_CS_PIN // // LCD / Controller @@ -170,14 +170,14 @@ */ #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN P1_31 - #define BTN_EN1 P3_26 - #define BTN_EN2 P3_25 - #define BTN_ENC P1_30 - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 - #define KILL_PIN P2_11 + #define BEEPER_PIN P1_31 + #define BTN_EN1 P3_26 + #define BTN_EN2 P3_25 + #define BTN_ENC P1_30 + #define LCD_PINS_RS P0_16 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 + #define KILL_PIN P2_11 #elif HAS_SPI_LCD #error "Only the CR10_STOCKDISPLAY is supported with TH3D EZBoard." #endif diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h index de064559af..7b0c0010a3 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h @@ -33,46 +33,46 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 2 -#define Z_STOP_PIN 5 +#define X_STOP_PIN 3 +#define Y_STOP_PIN 2 +#define Z_STOP_PIN 5 // // Steppers // -#define X_STEP_PIN 14 -#define X_DIR_PIN 15 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 14 +#define X_DIR_PIN 15 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 35 -#define Y_DIR_PIN 36 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN 35 +#define Y_DIR_PIN 36 +#define Y_ENABLE_PIN 31 -#define Z_STEP_PIN 40 -#define Z_DIR_PIN 41 -#define Z_ENABLE_PIN 37 +#define Z_STEP_PIN 40 +#define Z_DIR_PIN 41 +#define Z_ENABLE_PIN 37 -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 25 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 25 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 // // Temperature sensors // -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 14 // Analog Input -#define TEMP_BED_PIN 13 // Analog Input +#define TEMP_0_PIN 15 // Analog Input +#define TEMP_1_PIN 14 // Analog Input +#define TEMP_BED_PIN 13 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 19 // EXTRUDER 1 -#define HEATER_1_PIN 23 // EXTRUDER 2 -#define HEATER_BED_PIN 22 +#define HEATER_0_PIN 19 // EXTRUDER 1 +#define HEATER_1_PIN 23 // EXTRUDER 2 +#define HEATER_BED_PIN 22 // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h index 5fd5bfdef1..d56d08c9e0 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h @@ -36,101 +36,101 @@ // // Limit Switches // -#define X_MIN_PIN 30 -#define X_MAX_PIN 31 -#define Y_MIN_PIN 32 -#define Y_MAX_PIN 33 -#define Z_MIN_PIN 34 -#define Z_MAX_PIN 35 +#define X_MIN_PIN 30 +#define X_MAX_PIN 31 +#define Y_MIN_PIN 32 +#define Y_MAX_PIN 33 +#define Z_MIN_PIN 34 +#define Z_MAX_PIN 35 // // Steppers // -#define X_STEP_PIN 17 -#define X_DIR_PIN 16 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN 17 +#define X_DIR_PIN 16 +#define X_ENABLE_PIN 48 -#define Y_STEP_PIN 54 -#define Y_DIR_PIN 47 -#define Y_ENABLE_PIN 55 +#define Y_STEP_PIN 54 +#define Y_DIR_PIN 47 +#define Y_ENABLE_PIN 55 -#define Z_STEP_PIN 57 -#define Z_DIR_PIN 56 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 57 +#define Z_DIR_PIN 56 +#define Z_ENABLE_PIN 62 -#define E0_STEP_PIN 23 -#define E0_DIR_PIN 22 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 23 +#define E0_DIR_PIN 22 +#define E0_ENABLE_PIN 24 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 25 -#define E1_ENABLE_PIN 27 +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 25 +#define E1_ENABLE_PIN 27 -#define E2_STEP_PIN 29 -#define E2_DIR_PIN 28 -#define E2_ENABLE_PIN 39 +#define E2_STEP_PIN 29 +#define E2_DIR_PIN 28 +#define E2_ENABLE_PIN 39 // // Temperature sensors // -#define TEMP_0_PIN 15 -#define TEMP_1_PIN 13 -#define TEMP_2_PIN 14 -#define TEMP_3_PIN 11 // should be used for chamber temperature control -#define TEMP_BED_PIN 12 +#define TEMP_0_PIN 15 +#define TEMP_1_PIN 13 +#define TEMP_2_PIN 14 +#define TEMP_3_PIN 11 // should be used for chamber temperature control +#define TEMP_BED_PIN 12 // // Heaters / Fans // -#define HEATER_0_PIN 6 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 8 -#define HEATER_BED_PIN 9 +#define HEATER_0_PIN 6 +#define HEATER_1_PIN 7 +#define HEATER_2_PIN 8 +#define HEATER_BED_PIN 9 #ifndef FAN_PIN - #define FAN_PIN 3 + #define FAN_PIN 3 #endif -#define FAN2_PIN 58 // additional fan or light control output +#define FAN2_PIN 58 // additional fan or light control output // // Other board specific pins // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 37 // board input labeled as F-DET + #define FIL_RUNOUT_PIN 37 // board input labeled as F-DET #endif -#define Z_MIN_PROBE_PIN 36 // additional external board input labeled as E-SENS (should be used for Z-probe) -#define LED_PIN 13 -#define SPINDLE_ENABLE_PIN 4 // additional PWM pin 1 at JP1 connector - should be used for laser control too -#define EXT_2 5 // additional PWM pin 2 at JP1 connector -#define EXT_3 2 // additional PWM pin 3 at JP1 connector -#define PS_ON_PIN 45 -#define KILL_PIN 46 +#define Z_MIN_PROBE_PIN 36 // additional external board input labeled as E-SENS (should be used for Z-probe) +#define LED_PIN 13 +#define SPINDLE_ENABLE_PIN 4 // additional PWM pin 1 at JP1 connector - should be used for laser control too +#define EXT_2 5 // additional PWM pin 2 at JP1 connector +#define EXT_3 2 // additional PWM pin 3 at JP1 connector +#define PS_ON_PIN 45 +#define KILL_PIN 46 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 11 // shared with TEMP_3 analog input + #define FILWIDTH_PIN 11 // shared with TEMP_3 analog input #endif // // LCD / Controller // -#define LCD_PINS_RS 19 -#define LCD_PINS_ENABLE 42 -#define LCD_PINS_D4 18 -#define LCD_PINS_D5 38 -#define LCD_PINS_D6 41 -#define LCD_PINS_D7 40 +#define LCD_PINS_RS 19 +#define LCD_PINS_ENABLE 42 +#define LCD_PINS_D4 18 +#define LCD_PINS_D5 38 +#define LCD_PINS_D6 41 +#define LCD_PINS_D7 40 // // Beeper, SD Card, Encoder // -#define BEEPER_PIN 44 +#define BEEPER_PIN 44 #if ENABLED(SDSUPPORT) - #define SDSS 53 - #define SD_DETECT_PIN 49 + #define SDSS 53 + #define SD_DETECT_PIN 49 #endif #if ENABLED(NEWPANEL) - #define BTN_EN1 11 - #define BTN_EN2 12 - #define BTN_ENC 43 + #define BTN_EN1 11 + #define BTN_EN2 12 + #define BTN_ENC 43 #endif diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index 047dc8ef5a..833499fe0f 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -34,115 +34,115 @@ // // Limit Switches // -#define X_STOP_PIN 43 -#define Y_STOP_PIN 45 -#define Z_STOP_PIN 42 +#define X_STOP_PIN 43 +#define Y_STOP_PIN 45 +#define Z_STOP_PIN 42 // // Steppers // -#define X_STEP_PIN 34 -#define X_DIR_PIN 36 -#define X_ENABLE_PIN 35 +#define X_STEP_PIN 34 +#define X_DIR_PIN 36 +#define X_ENABLE_PIN 35 -#define Y_STEP_PIN 37 -#define Y_DIR_PIN 39 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 37 +#define Y_DIR_PIN 39 +#define Y_ENABLE_PIN 38 -#define Z_STEP_PIN 40 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 41 +#define Z_STEP_PIN 40 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 41 -#define E0_STEP_PIN 29 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 3 +#define E0_STEP_PIN 29 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 3 -#define E1_STEP_PIN 61 -#define E1_DIR_PIN 62 -#define E1_ENABLE_PIN 60 +#define E1_STEP_PIN 61 +#define E1_DIR_PIN 62 +#define E1_ENABLE_PIN 60 -#define E2_STEP_PIN 15 -#define E2_DIR_PIN 14 -#define E2_ENABLE_PIN 16 +#define E2_STEP_PIN 15 +#define E2_DIR_PIN 14 +#define E2_ENABLE_PIN 16 -#define E3_STEP_PIN 44 -#define E3_DIR_PIN 49 -#define E3_ENABLE_PIN 47 +#define E3_STEP_PIN 44 +#define E3_DIR_PIN 49 +#define E3_ENABLE_PIN 47 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 3 // Analog Input. 3 for tool2 -> 2 for chambertemp -#define TEMP_2_PIN 2 // Analog Input. 9 for tool3 -> 2 for chambertemp -#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 2 for chambertemp -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 3 // Analog Input. 3 for tool2 -> 2 for chambertemp +#define TEMP_2_PIN 2 // Analog Input. 9 for tool3 -> 2 for chambertemp +#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 2 for chambertemp +#define TEMP_BED_PIN 1 // Analog Input #ifndef TEMP_CHAMBER_PIN - //#define TEMP_CHAMBER_PIN 2 // Analog Input + //#define TEMP_CHAMBER_PIN 2 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 5 -#define HEATER_1_PIN 58 -#define HEATER_2_PIN 64 -#define HEATER_3_PIN 46 -#define HEATER_BED_PIN 2 +#define HEATER_0_PIN 5 +#define HEATER_1_PIN 58 +#define HEATER_2_PIN 64 +#define HEATER_3_PIN 46 +#define HEATER_BED_PIN 2 #ifndef FAN_PIN - //#define FAN_PIN 7 // common PWM pin for all tools + //#define FAN_PIN 7 // common PWM pin for all tools #endif -#define ORIG_E0_AUTO_FAN_PIN 7 -#define ORIG_E1_AUTO_FAN_PIN 7 -#define ORIG_E2_AUTO_FAN_PIN 7 -#define ORIG_E3_AUTO_FAN_PIN 7 +#define ORIG_E0_AUTO_FAN_PIN 7 +#define ORIG_E1_AUTO_FAN_PIN 7 +#define ORIG_E2_AUTO_FAN_PIN 7 +#define ORIG_E3_AUTO_FAN_PIN 7 // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 13 +#define SDSS 53 +#define SD_DETECT_PIN 13 // Tools -//#define TOOL_0_PIN 4 -//#define TOOL_1_PIN 59 -//#define TOOL_2_PIN 8 -//#define TOOL_3_PIN 30 -//#define TOOL_PWM_PIN 7 // common PWM pin for all tools +//#define TOOL_0_PIN 4 +//#define TOOL_1_PIN 59 +//#define TOOL_2_PIN 8 +//#define TOOL_3_PIN 30 +//#define TOOL_PWM_PIN 7 // common PWM pin for all tools // Common I/O -//#define FIL_RUNOUT_PIN -1 -//#define PWM_1_PIN 11 -//#define PWM_2_PIN 10 -//#define SPARE_IO 12 +//#define FIL_RUNOUT_PIN -1 +//#define PWM_1_PIN 11 +//#define PWM_2_PIN 10 +//#define SPARE_IO 12 // // LCD / Controller // -#define BEEPER_PIN 6 +#define BEEPER_PIN 6 // Pins for DOGM SPI LCD Support -#define DOGLCD_A0 26 -#define DOGLCD_CS 24 -#define DOGLCD_MOSI -1 -#define DOGLCD_SCK -1 +#define DOGLCD_A0 26 +#define DOGLCD_CS 24 +#define DOGLCD_MOSI -1 +#define DOGLCD_SCK -1 -#define BTN_EN1 23 -#define BTN_EN2 25 -#define BTN_ENC 27 +#define BTN_EN1 23 +#define BTN_EN2 25 +#define BTN_ENC 27 // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT 19 -#define SHIFT_LD 18 -#define SHIFT_CLK 17 +#define SHIFT_OUT 19 +#define SHIFT_LD 18 +#define SHIFT_CLK 17 -//#define UI1 31 -//#define UI2 22 +//#define UI1 31 +//#define UI2 22 -#define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 31 +#define STAT_LED_BLUE_PIN -1 +#define STAT_LED_RED_PIN 31 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 246a5964f0..680a5c9a99 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -34,122 +34,122 @@ // // Limit Switches // -#define X_STOP_PIN 19 -#define Y_STOP_PIN 22 -#define Z_STOP_PIN 23 +#define X_STOP_PIN 19 +#define Y_STOP_PIN 22 +#define Z_STOP_PIN 23 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 27 -#define X_ENABLE_PIN 26 +#define X_STEP_PIN 25 +#define X_DIR_PIN 27 +#define X_ENABLE_PIN 26 -#define Y_STEP_PIN 28 -#define Y_DIR_PIN 30 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN 28 +#define Y_DIR_PIN 30 +#define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 31 -#define Z_DIR_PIN 33 -#define Z_ENABLE_PIN 32 +#define Z_STEP_PIN 31 +#define Z_DIR_PIN 33 +#define Z_ENABLE_PIN 32 -#define E0_STEP_PIN 57 -#define E0_DIR_PIN 55 -#define E0_ENABLE_PIN 58 +#define E0_STEP_PIN 57 +#define E0_DIR_PIN 55 +#define E0_ENABLE_PIN 58 -#define E1_STEP_PIN 61 -#define E1_DIR_PIN 62 -#define E1_ENABLE_PIN 60 +#define E1_STEP_PIN 61 +#define E1_DIR_PIN 62 +#define E1_ENABLE_PIN 60 -#define E2_STEP_PIN 46 -#define E2_DIR_PIN 66 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN 46 +#define E2_DIR_PIN 66 +#define E2_ENABLE_PIN 44 -#define E3_STEP_PIN 45 -#define E3_DIR_PIN 69 -#define E3_ENABLE_PIN 47 +#define E3_STEP_PIN 45 +#define E3_DIR_PIN 69 +#define E3_ENABLE_PIN 47 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 9 // Analog Input. 9 for tool2 -> 13 for chambertemp -#define TEMP_2_PIN 13 // Analog Input. 10 for tool3 -> 13 for chambertemp -#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 13 for chambertemp -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 9 // Analog Input. 9 for tool2 -> 13 for chambertemp +#define TEMP_2_PIN 13 // Analog Input. 10 for tool3 -> 13 for chambertemp +#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 13 for chambertemp +#define TEMP_BED_PIN 14 // Analog Input #ifndef TEMP_CHAMBER_PIN - //#define TEMP_CHAMBER_PIN 13 // Analog Input + //#define TEMP_CHAMBER_PIN 13 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 11 -#define HEATER_1_PIN 9 -#define HEATER_2_PIN 6 -#define HEATER_3_PIN 3 -#define HEATER_BED_PIN 24 +#define HEATER_0_PIN 11 +#define HEATER_1_PIN 9 +#define HEATER_2_PIN 6 +#define HEATER_3_PIN 3 +#define HEATER_BED_PIN 24 #ifndef FAN_PIN - #define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools + #define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools #endif -#define ORIG_E0_AUTO_FAN_PIN 7 -#define ORIG_E1_AUTO_FAN_PIN 7 -#define ORIG_E2_AUTO_FAN_PIN 7 -#define ORIG_E3_AUTO_FAN_PIN 7 +#define ORIG_E0_AUTO_FAN_PIN 7 +#define ORIG_E1_AUTO_FAN_PIN 7 +#define ORIG_E2_AUTO_FAN_PIN 7 +#define ORIG_E3_AUTO_FAN_PIN 7 // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 15 +#define SDSS 53 +#define SD_DETECT_PIN 15 // Tools -//#define TOOL_0_PIN 56 -//#define TOOL_0_PWM_PIN 10 // red warning led at dual extruder -//#define TOOL_1_PIN 59 -//#define TOOL_1_PWM_PIN 8 // lights at dual extruder -//#define TOOL_2_PIN 4 -//#define TOOL_2_PWM_PIN 5 -//#define TOOL_3_PIN 14 -//#define TOOL_3_PWM_PIN 2 +//#define TOOL_0_PIN 56 +//#define TOOL_0_PWM_PIN 10 // red warning led at dual extruder +//#define TOOL_1_PIN 59 +//#define TOOL_1_PWM_PIN 8 // lights at dual extruder +//#define TOOL_2_PIN 4 +//#define TOOL_2_PWM_PIN 5 +//#define TOOL_3_PIN 14 +//#define TOOL_3_PWM_PIN 2 // Common I/O #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 18 + #define FIL_RUNOUT_PIN 18 #endif -//#define PWM_1_PIN 12 -//#define PWM_2_PIN 13 -//#define SPARE_IO 17 +//#define PWM_1_PIN 12 +//#define PWM_2_PIN 13 +//#define SPARE_IO 17 // // LCD / Controller // -#define BEEPER_PIN 16 +#define BEEPER_PIN 16 // Pins for DOGM SPI LCD Support -#define DOGLCD_A0 39 -#define DOGLCD_CS 35 -#define DOGLCD_MOSI 48 -#define DOGLCD_SCK 49 +#define DOGLCD_A0 39 +#define DOGLCD_CS 35 +#define DOGLCD_MOSI 48 +#define DOGLCD_SCK 49 #define LCD_SCREEN_ROT_180 // The encoder and click button -#define BTN_EN1 36 -#define BTN_EN2 34 -#define BTN_ENC 38 +#define BTN_EN1 36 +#define BTN_EN2 34 +#define BTN_ENC 38 // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT 42 -#define SHIFT_LD 41 -#define SHIFT_CLK 40 +#define SHIFT_OUT 42 +#define SHIFT_LD 41 +#define SHIFT_CLK 40 -//#define UI1 43 -//#define UI2 37 +//#define UI1 43 +//#define UI2 37 -#define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 10 // TOOL_0_PWM_PIN +#define STAT_LED_BLUE_PIN -1 +#define STAT_LED_RED_PIN 10 // TOOL_0_PWM_PIN diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index bf7d65f7e7..b4aa8ab815 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -34,79 +34,79 @@ // // Servos // -#define SERVO0_PIN 6 +#define SERVO0_PIN 6 // // Limit Switches // -#define X_STOP_PIN 34 -#define Y_STOP_PIN 39 -#define Z_STOP_PIN 62 +#define X_STOP_PIN 34 +#define Y_STOP_PIN 39 +#define Z_STOP_PIN 62 #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 + #define Z_MIN_PROBE_PIN 49 #endif // // Steppers // -#define X_STEP_PIN 14 -#define X_DIR_PIN 25 -#define X_ENABLE_PIN 26 +#define X_STEP_PIN 14 +#define X_DIR_PIN 25 +#define X_ENABLE_PIN 26 -#define Y_STEP_PIN 11 -#define Y_DIR_PIN 12 -#define Y_ENABLE_PIN 15 +#define Y_STEP_PIN 11 +#define Y_DIR_PIN 12 +#define Y_ENABLE_PIN 15 -#define Z_STEP_PIN 24 -#define Z_DIR_PIN 27 -#define Z_ENABLE_PIN 28 +#define Z_STEP_PIN 24 +#define Z_DIR_PIN 27 +#define Z_ENABLE_PIN 28 -#define E0_STEP_PIN 64 -#define E0_DIR_PIN 65 -#define E0_ENABLE_PIN 63 +#define E0_STEP_PIN 64 +#define E0_DIR_PIN 65 +#define E0_ENABLE_PIN 63 // // Temperature Sensors // Analog Inputs // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_BED_PIN 4 // Analog Input +#define TEMP_0_PIN 2 // Analog Input +#define TEMP_BED_PIN 4 // Analog Input #ifndef TEMP_CHAMBER_PIN - #define TEMP_CHAMBER_PIN 5 // Analog Input + #define TEMP_CHAMBER_PIN 5 // Analog Input #endif // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 32 -#define HEATER_CHAMBER_PIN 33 +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 32 +#define HEATER_CHAMBER_PIN 33 // // Fans // -#define FAN_PIN 8 -#define ORIG_E0_AUTO_FAN_PIN 30 -#define ORIG_E1_AUTO_FAN_PIN 30 -#define ORIG_E2_AUTO_FAN_PIN 30 -#define ORIG_E3_AUTO_FAN_PIN 30 -//#define ORIG_CHAMBER_AUTO_FAN_PIN 10 +#define FAN_PIN 8 +#define ORIG_E0_AUTO_FAN_PIN 30 +#define ORIG_E1_AUTO_FAN_PIN 30 +#define ORIG_E2_AUTO_FAN_PIN 30 +#define ORIG_E3_AUTO_FAN_PIN 30 +//#define ORIG_CHAMBER_AUTO_FAN_PIN 10 // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 40 +#define SDSS 53 +#define SD_DETECT_PIN 40 // Common I/O -#define FIL_RUNOUT_PIN 9 -//#define FIL_RUNOUT_PIN 29 // encoder sensor -//#define PWM_1_PIN 12 -//#define PWM_2_PIN 13 -//#define SPARE_IO 17 -#define BEEPER_PIN 13 -#define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 10 // 31 +#define FIL_RUNOUT_PIN 9 +//#define FIL_RUNOUT_PIN 29 // encoder sensor +//#define PWM_1_PIN 12 +//#define PWM_2_PIN 13 +//#define SPARE_IO 17 +#define BEEPER_PIN 13 +#define STAT_LED_BLUE_PIN -1 +#define STAT_LED_RED_PIN 10 // 31 diff --git a/Marlin/src/pins/mega/pins_EINSTART-S.h b/Marlin/src/pins/mega/pins_EINSTART-S.h index 45b500363e..8bb8f081f5 100644 --- a/Marlin/src/pins/mega/pins_EINSTART-S.h +++ b/Marlin/src/pins/mega/pins_EINSTART-S.h @@ -35,48 +35,48 @@ // // Limit Switches // -#define X_STOP_PIN 44 -#define Y_STOP_PIN 43 -#define Z_STOP_PIN 42 +#define X_STOP_PIN 44 +#define Y_STOP_PIN 43 +#define Z_STOP_PIN 42 // // Steppers // -#define X_STEP_PIN 76 -#define X_DIR_PIN 75 -#define X_ENABLE_PIN 73 +#define X_STEP_PIN 76 +#define X_DIR_PIN 75 +#define X_ENABLE_PIN 73 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 32 -#define Y_ENABLE_PIN 72 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 32 +#define Y_ENABLE_PIN 72 -#define Z_STEP_PIN 34 -#define Z_DIR_PIN 35 -#define Z_ENABLE_PIN 33 +#define Z_STEP_PIN 34 +#define Z_DIR_PIN 35 +#define Z_ENABLE_PIN 33 -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 37 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 37 +#define E0_ENABLE_PIN 30 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_BED_PIN 1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 83 -#define HEATER_BED_PIN 38 +#define HEATER_0_PIN 83 +#define HEATER_BED_PIN 38 -#define FAN_PIN 82 +#define FAN_PIN 82 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 4 +#define SDSS 53 +#define LED_PIN 4 ////////////////////////// // LCDs and Controllers // @@ -90,24 +90,24 @@ // u8glib constructor // U8GLIB_SH1106_128X64 u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, LCD_PINS_DC, LCD_PINS_RS); -#define LCD_PINS_DC 78 -#define LCD_PINS_RS 79 +#define LCD_PINS_DC 78 +#define LCD_PINS_RS 79 // DOGM SPI LCD Support -#define DOGLCD_CS 3 -#define DOGLCD_MOSI 2 -#define DOGLCD_SCK 5 -#define DOGLCD_A0 2 +#define DOGLCD_CS 3 +#define DOGLCD_MOSI 2 +#define DOGLCD_SCK 5 +#define DOGLCD_A0 2 // // LCD Display input pins // -#define BTN_UP 25 -#define BTN_DWN 26 -#define BTN_LFT 27 -#define BTN_RT 28 +#define BTN_UP 25 +#define BTN_DWN 26 +#define BTN_LFT 27 +#define BTN_RT 28 // 'OK' button -#define BTN_ENC 29 +#define BTN_ENC 29 // Set Kill to right arrow, same as RIGID_PANEL -#define KILL_PIN 28 +#define KILL_PIN 28 diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index 30b4ab40af..3d35a72b19 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -34,115 +34,115 @@ // // Limit Switches // -#define X_MIN_PIN 35 -#define X_MAX_PIN 34 -#define Y_MIN_PIN 33 -#define Y_MAX_PIN 32 -#define Z_MIN_PIN 31 -#define Z_MAX_PIN 30 +#define X_MIN_PIN 35 +#define X_MAX_PIN 34 +#define Y_MIN_PIN 33 +#define Y_MAX_PIN 32 +#define Z_MIN_PIN 31 +#define Z_MAX_PIN 30 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 30 + #define Z_MIN_PROBE_PIN 30 #endif // // Steppers // -#define X_STEP_PIN 49 -#define X_DIR_PIN 13 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN 49 +#define X_DIR_PIN 13 +#define X_ENABLE_PIN 48 -#define Y_STEP_PIN 11 -#define Y_DIR_PIN 9 -#define Y_ENABLE_PIN 12 +#define Y_STEP_PIN 11 +#define Y_DIR_PIN 9 +#define Y_ENABLE_PIN 12 -#define Z_STEP_PIN 7 -#define Z_DIR_PIN 6 -#define Z_ENABLE_PIN 8 +#define Z_STEP_PIN 7 +#define Z_DIR_PIN 6 +#define Z_ENABLE_PIN 8 -#define E0_STEP_PIN 40 -#define E0_DIR_PIN 41 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN 40 +#define E0_DIR_PIN 41 +#define E0_ENABLE_PIN 37 -#define E1_STEP_PIN 18 -#define E1_DIR_PIN 19 -#define E1_ENABLE_PIN 38 +#define E1_STEP_PIN 18 +#define E1_DIR_PIN 19 +#define E1_ENABLE_PIN 38 -#define E2_STEP_PIN 43 -#define E2_DIR_PIN 47 -#define E2_ENABLE_PIN 42 +#define E2_STEP_PIN 43 +#define E2_DIR_PIN 47 +#define E2_ENABLE_PIN 42 // // Temperature Sensors // -#define TEMP_0_PIN 3 // Analog Input -#define TEMP_1_PIN 2 // Analog Input -#define TEMP_2_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN 3 // Analog Input +#define TEMP_1_PIN 2 // Analog Input +#define TEMP_2_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 45 // 12V PWM1 -#define HEATER_1_PIN 46 // 12V PWM2 -#define HEATER_2_PIN 17 // 12V PWM3 -#define HEATER_BED_PIN 44 // DOUBLE 12V PWM +#define HEATER_0_PIN 45 // 12V PWM1 +#define HEATER_1_PIN 46 // 12V PWM2 +#define HEATER_2_PIN 17 // 12V PWM3 +#define HEATER_BED_PIN 44 // DOUBLE 12V PWM #ifndef FAN_PIN - #define FAN_PIN 16 // 5V PWM + #define FAN_PIN 16 // 5V PWM #endif // // Misc. Functions // -#define PS_ON_PIN 10 // Set to -1 if using a manual switch on the PWRSW Connector -#define SLEEP_WAKE_PIN 26 // This feature still needs work -#define PHOTOGRAPH_PIN 29 +#define PS_ON_PIN 10 // Set to -1 if using a manual switch on the PWRSW Connector +#define SLEEP_WAKE_PIN 26 // This feature still needs work +#define PHOTOGRAPH_PIN 29 // // LCD / Controller // -#define BEEPER_PIN 36 +#define BEEPER_PIN 36 #if ENABLED(RA_CONTROL_PANEL) - #define SDSS 53 - #define SD_DETECT_PIN 28 + #define SDSS 53 + #define SD_DETECT_PIN 28 - #define BTN_EN1 14 - #define BTN_EN2 39 - #define BTN_ENC 15 + #define BTN_EN1 14 + #define BTN_EN2 39 + #define BTN_ENC 15 #endif // RA_CONTROL_PANEL #if ENABLED(RA_DISCO) // variables for which pins the TLC5947 is using - #define TLC_CLOCK_PIN 25 - #define TLC_BLANK_PIN 23 - #define TLC_XLAT_PIN 22 - #define TLC_DATA_PIN 24 + #define TLC_CLOCK_PIN 25 + #define TLC_BLANK_PIN 23 + #define TLC_XLAT_PIN 22 + #define TLC_DATA_PIN 24 // We also need to define pin to port number mapping for the 2560 to match the pins listed above. // If you change the TLC pins, update this as well per the 2560 datasheet! This currently only works with the RA Board. - #define TLC_CLOCK_BIT 3 + #define TLC_CLOCK_BIT 3 #define TLC_CLOCK_PORT &PORTA - #define TLC_BLANK_BIT 1 + #define TLC_BLANK_BIT 1 #define TLC_BLANK_PORT &PORTA - #define TLC_DATA_BIT 2 + #define TLC_DATA_BIT 2 #define TLC_DATA_PORT &PORTA - #define TLC_XLAT_BIT 0 + #define TLC_XLAT_BIT 0 #define TLC_XLAT_PORT &PORTA // Change this to match your situation. Lots of TLCs takes up the arduino SRAM very quickly, so be careful // Leave it at at least 1 if you have enabled RA_LIGHTING // The number of TLC5947 boards chained together for use with the animation, additional ones will repeat the animation on them, but are not individually addressable and mimic those before them. You can leave the default at 2 even if you only have 1 TLC5947 module. - #define NUM_TLCS 2 + #define NUM_TLCS 2 // These TRANS_ARRAY values let you change the order the LEDs on the lighting modules will animate for chase functions. // Modify them according to your specific situation. diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index 6590f06d6c..e111f2ce44 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -39,102 +39,102 @@ // // Limit Switches // -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN 32 +#define X_MIN_PIN 22 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 26 +#define Y_MAX_PIN 28 +#define Z_MIN_PIN 30 +#define Z_MAX_PIN 32 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN 37 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 35 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN 43 +#define E0_DIR_PIN 45 +#define E0_ENABLE_PIN 41 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 // // Temperature Sensors // -#define TEMP_0_PIN 8 -#define TEMP_1_PIN 9 -#define TEMP_BED_PIN 10 +#define TEMP_0_PIN 8 +#define TEMP_1_PIN 9 +#define TEMP_BED_PIN 10 // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN 7 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing -#define KILL_PIN -1 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 +#define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing +#define KILL_PIN -1 #if HAS_SPI_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN 18 #if ENABLED(NEWPANEL) #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 5 - #define DOGLCD_CS 21 - #define BTN_EN1 40 - #define BTN_EN2 42 + #define DOGLCD_A0 5 + #define DOGLCD_CS 21 + #define BTN_EN1 40 + #define BTN_EN2 42 #else - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 16 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 + #define BTN_EN1 42 + #define BTN_EN2 40 #endif - #define BTN_ENC 19 - #define SD_DETECT_PIN 38 + #define BTN_ENC 19 + #define SD_DETECT_PIN 38 - #else // !NEWPANEL + #else // !NEWPANEL - #define SHIFT_CLK 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK 38 + #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_EN 17 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 20 + #define LCD_PINS_D7 19 - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #endif // !NEWPANEL diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 566e88705d..08f9018a29 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -36,33 +36,33 @@ // // Servos // -#define SERVO0_PIN 11 //13 untested 3Dtouch +#define SERVO0_PIN 11 //13 untested 3Dtouch // // Limit Switches // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN 24 + #define X_MIN_PIN 24 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 22 + #define X_MAX_PIN 22 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN 28 + #define Y_MIN_PIN 28 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 26 + #define Y_MAX_PIN 26 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN 30 + #define Z_MIN_PIN 30 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 32 + #define Z_MAX_PIN 32 #endif #endif @@ -70,116 +70,116 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 66 + #define FIL_RUNOUT_PIN 66 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN 67 + #define FIL_RUNOUT2_PIN 67 #endif // // Power Recovery // -#define POWER_LOSS_PIN 69 // Pin to detect power loss -#define POWER_LOSS_STATE LOW +#define POWER_LOSS_PIN 69 // Pin to detect power loss +#define POWER_LOSS_STATE LOW // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 39 -#define X_ENABLE_PIN 35 +#define X_STEP_PIN 37 +#define X_DIR_PIN 39 +#define X_ENABLE_PIN 35 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 25 -#define Z_DIR_PIN 23 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN 25 +#define Z_DIR_PIN 23 +#define Z_ENABLE_PIN 27 -#define E0_STEP_PIN 46 -#define E0_DIR_PIN 44 -#define E0_ENABLE_PIN 12 +#define E0_STEP_PIN 46 +#define E0_DIR_PIN 44 +#define E0_ENABLE_PIN 12 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 -#define E2_STEP_PIN 43 -#define E2_DIR_PIN 45 -#define E2_ENABLE_PIN 41 +#define E2_STEP_PIN 43 +#define E2_DIR_PIN 45 +#define E2_ENABLE_PIN 41 // // Temperature Sensors // -#define TEMP_0_PIN 11 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_2_PIN 1 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 11 // Analog Input +#define TEMP_1_PIN 9 // Analog Input +#define TEMP_2_PIN 1 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 3 -#define HEATER_2_PIN 1 -#define HEATER_BED_PIN 4 -#define FAN_PIN 9 -#define FAN1_PIN 8 -#define FAN2_PIN 7 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 3 +#define HEATER_2_PIN 1 +#define HEATER_BED_PIN 4 +#define FAN_PIN 9 +#define FAN1_PIN 8 +#define FAN2_PIN 7 // // Misc. Functions // -#define SD_DETECT_PIN 38 -#define SDSS 53 -#define LED_PIN 6 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // This pin must be enabled at boot to keep power flowing +#define SD_DETECT_PIN 38 +#define SDSS 53 +#define LED_PIN 6 +#define PS_ON_PIN 12 +#define SUICIDE_PIN 54 // This pin must be enabled at boot to keep power flowing #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 6 // 21 + #define CASE_LIGHT_PIN 6 // 21 #endif // // LCD Controller // -#define BEEPER_PIN 18 +#define BEEPER_PIN 18 #ifndef LCD_PINS_RS - #define LCD_PINS_RS 20 + #define LCD_PINS_RS 20 #endif #ifndef LCD_PINS_ENABLE - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_ENABLE 17 #endif #ifndef LCD_PINS_D4 - #define LCD_PINS_D4 16 + #define LCD_PINS_D4 16 #endif #ifndef LCD_PINS_D5 - #define LCD_PINS_D5 21 + #define LCD_PINS_D5 21 #endif #ifndef LCD_PINS_D6 - #define LCD_PINS_D6 5 + #define LCD_PINS_D6 5 #endif #ifndef LCD_PINS_D7 - #define LCD_PINS_D7 36 + #define LCD_PINS_D7 36 #endif #if ENABLED(NEWPANEL) #ifndef BTN_EN1 - #define BTN_EN1 42 + #define BTN_EN1 42 #endif #ifndef BTN_EN2 - #define BTN_EN2 40 + #define BTN_EN2 40 #endif #ifndef BTN_ENC - #define BTN_ENC 19 + #define BTN_ENC 19 #endif #endif diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h index 037ea13244..06ac9fd9df 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h @@ -25,15 +25,15 @@ * Geeetech A20M pin assignment */ -#define LCD_PINS_RS 5 -#define LCD_PINS_ENABLE 36 -#define LCD_PINS_D4 21 -#define LCD_PINS_D7 6 +#define LCD_PINS_RS 5 +#define LCD_PINS_ENABLE 36 +#define LCD_PINS_D4 21 +#define LCD_PINS_D7 6 #if ENABLED(NEWPANEL) - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 19 + #define BTN_EN1 16 + #define BTN_EN2 17 + #define BTN_ENC 19 #endif #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h index 7ba9112d4e..0f06aaf256 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h @@ -27,9 +27,9 @@ #define BOARD_INFO_NAME "GT2560 V3.0 (MC2)" -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 +#define X_MIN_PIN 22 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 26 +#define Y_MAX_PIN 28 #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index b667566688..66adfb2fa7 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -42,79 +42,79 @@ // // Limit Switches // -#define X_STOP_PIN 22 -#define Y_STOP_PIN 26 -#define Z_STOP_PIN 29 -//#define EXP_STOP_PIN 28 +#define X_STOP_PIN 22 +#define Y_STOP_PIN 26 +#define Z_STOP_PIN 29 +//#define EXP_STOP_PIN 28 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Y_STEP_PIN 32 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN 32 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 31 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 36 -#define Z_ENABLE_PIN 34 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 36 +#define Z_ENABLE_PIN 34 -#define E0_STEP_PIN 42 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN 42 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 37 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 -#define MOTOR_CURRENT_PWM_XY_PIN 44 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 46 +#define MOTOR_CURRENT_PWM_XY_PIN 44 +#define MOTOR_CURRENT_PWM_Z_PIN 45 +#define MOTOR_CURRENT_PWM_E_PIN 46 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE - #define MOTOR_CURRENT_PWM_RANGE 2000 + #define MOTOR_CURRENT_PWM_RANGE 2000 #endif #define DEFAULT_PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 9 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 7 //默认不使用PWM_FAN冷却喷嘴,如果需要,则取消注释 + #define FAN_PIN 7 //默认不使用PWM_FAN冷却喷嘴,如果需要,则取消注释 #endif // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 39 -//#define LED_PIN 8 -#define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需要PWM FAN,则需要将FAN_PIN置为7,LED_PIN置为8 +#define SDSS 53 +#define SD_DETECT_PIN 39 +//#define LED_PIN 8 +#define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需要PWM FAN,则需要将FAN_PIN置为7,LED_PIN置为8 -//#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered -//#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. +//#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered +//#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. // // M3/M4/M5 - Spindle/Laser Control // #if ENABLED(SPINDLE_LASER_ENABLE) - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! - #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM + #define SPINDLE_DIR_PIN 16 + #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! + #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM #endif // @@ -122,48 +122,48 @@ // #if HAS_SPI_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN 18 #if ENABLED(NEWPANEL) - #define LCD_PINS_RS 20 // LCD_CS - #define LCD_PINS_ENABLE 15 // LCD_SDA - #define LCD_PINS_D4 14 // LCD_SCK + #define LCD_PINS_RS 20 // LCD_CS + #define LCD_PINS_ENABLE 15 // LCD_SDA + #define LCD_PINS_D4 14 // LCD_SCK #if ENABLED(HJC_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 5 // LCD_Backlight + #define LCD_BACKLIGHT_PIN 5 // LCD_Backlight //#ifndef LCD_CONTRAST_PIN // #define LCD_CONTRAST_PIN 5 // LCD_Contrast //#endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 24 // Filament runout + #define FIL_RUNOUT_PIN 24 // Filament runout #endif #else - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 #endif - #define BTN_EN1 41 - #define BTN_EN2 40 - #define BTN_ENC 19 + #define BTN_EN1 41 + #define BTN_EN2 40 + #define BTN_ENC 19 - #define SD_DETECT_PIN 39 + #define SD_DETECT_PIN 39 #else // Buttons attached to a shift register - #define SHIFT_CLK 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK 38 + #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_EN 17 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 20 + #define LCD_PINS_D7 19 #endif // !NEWPANEL diff --git a/Marlin/src/pins/mega/pins_LEAPFROG.h b/Marlin/src/pins/mega/pins_LEAPFROG.h index f04b89d4bc..188cbcad3d 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG.h @@ -34,59 +34,59 @@ // // Limit Switches // -#define X_MIN_PIN 47 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 48 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 49 -#define Z_MAX_PIN -1 +#define X_MIN_PIN 47 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 48 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 49 +#define Z_MAX_PIN -1 // // Steppers // -#define X_STEP_PIN 28 -#define X_DIR_PIN 63 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN 28 +#define X_DIR_PIN 63 +#define X_ENABLE_PIN 29 -#define Y_STEP_PIN 14 // A6 -#define Y_DIR_PIN 15 // A0 -#define Y_ENABLE_PIN 39 +#define Y_STEP_PIN 14 // A6 +#define Y_DIR_PIN 15 // A0 +#define Y_ENABLE_PIN 39 -#define Z_STEP_PIN 31 // A2 -#define Z_DIR_PIN 32 // A6 -#define Z_ENABLE_PIN 30 // A1 +#define Z_STEP_PIN 31 // A2 +#define Z_DIR_PIN 32 // A6 +#define Z_ENABLE_PIN 30 // A1 -#define E0_STEP_PIN 34 // 34 -#define E0_DIR_PIN 35 // 35 -#define E0_ENABLE_PIN 33 // 33 +#define E0_STEP_PIN 34 // 34 +#define E0_DIR_PIN 35 // 35 +#define E0_ENABLE_PIN 33 // 33 -#define E1_STEP_PIN 37 // 37 -#define E1_DIR_PIN 40 // 40 -#define E1_ENABLE_PIN 36 // 36 +#define E1_STEP_PIN 37 // 37 +#define E1_DIR_PIN 40 // 40 +#define E1_ENABLE_PIN 36 // 36 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input (D27) -#define TEMP_1_PIN 15 // Analog Input (1) -#define TEMP_BED_PIN 14 // Analog Input (1,2 or I2C) +#define TEMP_0_PIN 13 // Analog Input (D27) +#define TEMP_1_PIN 15 // Analog Input (1) +#define TEMP_BED_PIN 14 // Analog Input (1,2 or I2C) // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 // 12 -#define HEATER_2_PIN 11 // 13 -#define HEATER_BED_PIN 10 // 14/15 +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 8 // 12 +#define HEATER_2_PIN 11 // 13 +#define HEATER_BED_PIN 10 // 14/15 -#define FAN_PIN 7 +#define FAN_PIN 7 // // Misc. Functions // -#define SDSS 11 -#define LED_PIN 13 -#define SOL1_PIN 16 -#define SOL2_PIN 17 +#define SDSS 11 +#define LED_PIN 13 +#define SOL1_PIN 16 +#define SOL2_PIN 17 /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ diff --git a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h index ab6299a9b0..36cb0e2c14 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h @@ -38,9 +38,9 @@ // // Limit Switches // -#define X_STOP_PIN 47 // 'X Min' -#define Y_STOP_PIN 48 // 'Y Min' -#define Z_STOP_PIN 49 // 'Z Min' +#define X_STOP_PIN 47 // 'X Min' +#define Y_STOP_PIN 48 // 'Y Min' +#define Z_STOP_PIN 49 // 'Z Min' // // Steppers @@ -51,65 +51,65 @@ // // X-axis signal-level connector -#define X_STEP_PIN 65 -#define X_DIR_PIN 64 -#define X_ENABLE_PIN 66 // Not actually used on Xeed, could be repurposed +#define X_STEP_PIN 65 +#define X_DIR_PIN 64 +#define X_ENABLE_PIN 66 // Not actually used on Xeed, could be repurposed // Y-axis signal-level connector -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 // Not actually used on Xeed, could be repurposed +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 // Not actually used on Xeed, could be repurposed // ZMOT connector (Front Right Z Motor) -#define Z_STEP_PIN 31 -#define Z_DIR_PIN 32 -#define Z_ENABLE_PIN 30 +#define Z_STEP_PIN 31 +#define Z_DIR_PIN 32 +#define Z_ENABLE_PIN 30 // XMOT connector (Rear Z Motor) -#define Z2_STEP_PIN 28 -#define Z2_DIR_PIN 63 -#define Z2_ENABLE_PIN 29 +#define Z2_STEP_PIN 28 +#define Z2_DIR_PIN 63 +#define Z2_ENABLE_PIN 29 // YMOT connector (Front Left Z Motor) -#define Z3_STEP_PIN 14 -#define Z3_DIR_PIN 15 -#define Z3_ENABLE_PIN 39 +#define Z3_STEP_PIN 14 +#define Z3_DIR_PIN 15 +#define Z3_ENABLE_PIN 39 // EMOT2 connector -#define E0_STEP_PIN 37 -#define E0_DIR_PIN 40 -#define E0_ENABLE_PIN 36 +#define E0_STEP_PIN 37 +#define E0_DIR_PIN 40 +#define E0_ENABLE_PIN 36 // EMOT connector -#define E1_STEP_PIN 34 -#define E1_DIR_PIN 35 -#define E1_ENABLE_PIN 33 +#define E1_STEP_PIN 34 +#define E1_DIR_PIN 35 +#define E1_ENABLE_PIN 33 // // Filament runout // -#define FIL_RUNOUT_PIN 42 // ROT2 Connector -#define FIL_RUNOUT2_PIN 44 // ROT1 Connector +#define FIL_RUNOUT_PIN 42 // ROT2 Connector +#define FIL_RUNOUT2_PIN 44 // ROT1 Connector // // Temperature Sensors // -#define TEMP_0_PIN 15 // T3 Connector -#define TEMP_1_PIN 13 // T1 Connector -#define TEMP_BED_PIN 14 // BED Connector (Between T1 and T3) +#define TEMP_0_PIN 15 // T3 Connector +#define TEMP_1_PIN 13 // T1 Connector +#define TEMP_BED_PIN 14 // BED Connector (Between T1 and T3) // // Heaters / Fans // -#define HEATER_0_PIN 8 // Misc Connector, pins 3 and 4 (Out2) -#define HEATER_1_PIN 9 // Misc Connector, pins 5 and 6 (Out3) -#define HEATER_BED_PIN 6 // Misc Connector, pins 9(-) and 10(+) (OutA) +#define HEATER_0_PIN 8 // Misc Connector, pins 3 and 4 (Out2) +#define HEATER_1_PIN 9 // Misc Connector, pins 5 and 6 (Out3) +#define HEATER_BED_PIN 6 // Misc Connector, pins 9(-) and 10(+) (OutA) -#define FAN_PIN 10 // Misc Connector, pins 7(-) and 8 (+) (Out4) +#define FAN_PIN 10 // Misc Connector, pins 7(-) and 8 (+) (Out4) -#define LED_PIN 13 +#define LED_PIN 13 -#define SOL1_PIN 7 // Misc Connector, pins 1(-) and 2(+) (Out1) +#define SOL1_PIN 7 // Misc Connector, pins 1(-) and 2(+) (Out1) // Door Closed Sensor -//#define DOOR_PIN 45 // HM1 Connector +//#define DOOR_PIN 45 // HM1 Connector diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index 8fecc71bac..2d0db15825 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -36,89 +36,89 @@ // // Servos // -#define SERVO0_PIN 30 -#define SERVO1_PIN 31 -#define SERVO2_PIN 32 -#define SERVO3_PIN 33 +#define SERVO0_PIN 30 +#define SERVO1_PIN 31 +#define SERVO2_PIN 32 +#define SERVO3_PIN 33 // // Limit Switches // -#define X_MIN_PIN 43 -#define X_MAX_PIN 42 -#define Y_MIN_PIN 38 -#define Y_MAX_PIN 41 -#define Z_MIN_PIN 40 -#define Z_MAX_PIN 37 +#define X_MIN_PIN 43 +#define X_MAX_PIN 42 +#define Y_MIN_PIN 38 +#define Y_MAX_PIN 41 +#define Z_MIN_PIN 40 +#define Z_MAX_PIN 37 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 37 + #define Z_MIN_PROBE_PIN 37 #endif // // Steppers // -#define X_STEP_PIN 62 // A8 -#define X_DIR_PIN 63 // A9 -#define X_ENABLE_PIN 61 // A7 +#define X_STEP_PIN 62 // A8 +#define X_DIR_PIN 63 // A9 +#define X_ENABLE_PIN 61 // A7 -#define Y_STEP_PIN 65 // A11 -#define Y_DIR_PIN 66 // A12 -#define Y_ENABLE_PIN 64 // A10 +#define Y_STEP_PIN 65 // A11 +#define Y_DIR_PIN 66 // A12 +#define Y_ENABLE_PIN 64 // A10 -#define Z_STEP_PIN 68 // A14 -#define Z_DIR_PIN 69 // A15 -#define Z_ENABLE_PIN 67 // A13 +#define Z_STEP_PIN 68 // A14 +#define Z_DIR_PIN 69 // A15 +#define Z_ENABLE_PIN 67 // A13 -#define E0_STEP_PIN 23 -#define E0_DIR_PIN 24 -#define E0_ENABLE_PIN 22 +#define E0_STEP_PIN 23 +#define E0_DIR_PIN 24 +#define E0_ENABLE_PIN 22 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 27 -#define E1_ENABLE_PIN 25 +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 27 +#define E1_ENABLE_PIN 25 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 4 // Analog Input + #define TEMP_0_PIN 4 // Analog Input #else - #define TEMP_0_PIN 0 // Analog Input + #define TEMP_0_PIN 0 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 5 // Analog Input + #define TEMP_1_PIN 5 // Analog Input #else - #define TEMP_1_PIN 2 // Analog Input + #define TEMP_1_PIN 2 // Analog Input #endif -#define TEMP_2_PIN 3 // Analog Input +#define TEMP_2_PIN 3 // Analog Input #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 6 // Analog Input + #define TEMP_BED_PIN 6 // Analog Input #else - #define TEMP_BED_PIN 1 // Analog Input + #define TEMP_BED_PIN 1 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 29 -#define HEATER_1_PIN 34 -#define HEATER_BED_PIN 28 +#define HEATER_0_PIN 29 +#define HEATER_1_PIN 34 +#define HEATER_BED_PIN 28 #ifndef FAN_PIN - #define FAN_PIN 39 + #define FAN_PIN 39 #endif -#define FAN1_PIN 35 -#define FAN2_PIN 36 +#define FAN1_PIN 35 +#define FAN2_PIN 36 #ifndef CONTROLLER_FAN_PIN - #define CONTROLLER_FAN_PIN FAN2_PIN + #define CONTROLLER_FAN_PIN FAN2_PIN #endif #define FAN_SOFT_PWM @@ -126,39 +126,39 @@ // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define CASE_LIGHT_PIN 2 +#define SDSS 53 +#define LED_PIN 13 +#define CASE_LIGHT_PIN 2 // // LCD / Controller // #if ENABLED(MINIPANEL) - #define BEEPER_PIN 46 + #define BEEPER_PIN 46 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 47 - #define DOGLCD_CS 45 - #define LCD_BACKLIGHT_PIN 44 // backlight LED on PA3 + #define DOGLCD_A0 47 + #define DOGLCD_CS 45 + #define LCD_BACKLIGHT_PIN 44 // backlight LED on PA3 - #define KILL_PIN 12 + #define KILL_PIN 12 // GLCD features // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BTN_EN1 48 - #define BTN_EN2 11 - #define BTN_ENC 10 + #define BTN_EN1 48 + #define BTN_EN2 11 + #define BTN_ENC 10 - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #endif // MINIPANEL // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 7 // Pullup! -#define SPINDLE_DIR_PIN 8 +#define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 7 // Pullup! +#define SPINDLE_DIR_PIN 8 diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index d3015340de..4d7a980050 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -33,99 +33,99 @@ // // Limit Switches // -#define X_MIN_PIN 41 -#define X_MAX_PIN 37 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN 41 +#define X_MAX_PIN 37 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN 19 #endif // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 26 +#define X_DIR_PIN 28 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 60 // A6 -#define Y_DIR_PIN 61 // A7 -#define Y_ENABLE_PIN 22 +#define Y_STEP_PIN 60 // A6 +#define Y_DIR_PIN 61 // A7 +#define Y_ENABLE_PIN 22 -#define Z_STEP_PIN 54 // A0 -#define Z_DIR_PIN 55 // A1 -#define Z_ENABLE_PIN 56 // A2 +#define Z_STEP_PIN 54 // A0 +#define Z_DIR_PIN 55 // A1 +#define Z_ENABLE_PIN 56 // A2 -#define E0_STEP_PIN 31 -#define E0_DIR_PIN 32 -#define E0_ENABLE_PIN 38 +#define E0_STEP_PIN 31 +#define E0_DIR_PIN 32 +#define E0_ENABLE_PIN 38 -#define E1_STEP_PIN 34 -#define E1_DIR_PIN 36 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 34 +#define E1_DIR_PIN 36 +#define E1_ENABLE_PIN 30 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 8 // Analog Input + #define TEMP_0_PIN 8 // Analog Input #else - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN 13 // Analog Input #endif -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_BED_PIN 14 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 -#define HEATER_BED_PIN 10 +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 8 +#define HEATER_BED_PIN 10 #ifndef FAN_PIN - #define FAN_PIN 7 // IO pin. Buffer needed + #define FAN_PIN 7 // IO pin. Buffer needed #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 2 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 +#define CASE_LIGHT_PIN 2 // // LCD / Controller // -#define BEEPER_PIN 33 +#define BEEPER_PIN 33 #if BOTH(ULTRA_LCD, NEWPANEL) - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 // Buttons directly attached to AUX-2 - #define BTN_EN1 59 - #define BTN_EN2 64 - #define BTN_ENC 43 + #define BTN_EN1 59 + #define BTN_EN2 64 + #define BTN_ENC 43 - #define SD_DETECT_PIN -1 // RAMPS doesn't use this + #define SD_DETECT_PIN -1 // RAMPS doesn't use this #endif // HAS_SPI_LCD && NEWPANEL // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 4 // Pullup! -#define SPINDLE_DIR_PIN 11 +#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 4 // Pullup! +#define SPINDLE_DIR_PIN 11 diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index 160d9d4b78..d976e09816 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -33,120 +33,120 @@ // // Limit Switches // -#define X_MIN_PIN 37 -#define X_MAX_PIN 40 -#define Y_MIN_PIN 41 -#define Y_MAX_PIN 38 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN 37 +#define X_MAX_PIN 40 +#define Y_MIN_PIN 41 +#define Y_MAX_PIN 38 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN 19 #endif // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 27 -#define X_ENABLE_PIN 25 +#define X_STEP_PIN 26 +#define X_DIR_PIN 27 +#define X_ENABLE_PIN 25 -#define Y_STEP_PIN 4 // A6 -#define Y_DIR_PIN 54 // A0 -#define Y_ENABLE_PIN 5 +#define Y_STEP_PIN 4 // A6 +#define Y_DIR_PIN 54 // A0 +#define Y_ENABLE_PIN 5 -#define Z_STEP_PIN 56 // A2 -#define Z_DIR_PIN 60 // A6 -#define Z_ENABLE_PIN 55 // A1 +#define Z_STEP_PIN 56 // A2 +#define Z_DIR_PIN 60 // A6 +#define Z_ENABLE_PIN 55 // A1 -#define E0_STEP_PIN 35 -#define E0_DIR_PIN 36 -#define E0_ENABLE_PIN 34 +#define E0_STEP_PIN 35 +#define E0_DIR_PIN 36 +#define E0_ENABLE_PIN 34 -#define E1_STEP_PIN 29 -#define E1_DIR_PIN 39 -#define E1_ENABLE_PIN 28 +#define E1_STEP_PIN 29 +#define E1_DIR_PIN 39 +#define E1_ENABLE_PIN 28 -#define E2_STEP_PIN 23 // ? schematic says 24 -#define E2_DIR_PIN 24 // ? schematic says 23 -#define E2_ENABLE_PIN 22 +#define E2_STEP_PIN 23 // ? schematic says 24 +#define E2_DIR_PIN 24 // ? schematic says 23 +#define E2_ENABLE_PIN 22 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 4 // Analog Input + #define TEMP_0_PIN 4 // Analog Input #else - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN 13 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 8 // Analog Input + #define TEMP_1_PIN 8 // Analog Input #else - #define TEMP_1_PIN 15 // Analog Input + #define TEMP_1_PIN 15 // Analog Input #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 8 // Analog Input + #define TEMP_BED_PIN 8 // Analog Input #else - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN 14 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 -#define HEATER_BED_PIN 10 +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 8 +#define HEATER_BED_PIN 10 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN 7 #endif -#define FAN1_PIN 6 +#define FAN1_PIN 6 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 2 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 +#define CASE_LIGHT_PIN 2 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 16 // Pullup! -#define SPINDLE_DIR_PIN 11 +#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 16 // Pullup! +#define SPINDLE_DIR_PIN 11 // // LCD / Controller // -#define BEEPER_PIN 64 +#define BEEPER_PIN 64 #if HAS_SPI_LCD - #define LCD_PINS_RS 14 - #define LCD_PINS_ENABLE 15 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 31 - #define LCD_PINS_D6 32 - #define LCD_PINS_D7 33 + #define LCD_PINS_RS 14 + #define LCD_PINS_ENABLE 15 + #define LCD_PINS_D4 30 + #define LCD_PINS_D5 31 + #define LCD_PINS_D6 32 + #define LCD_PINS_D7 33 #if ENABLED(NEWPANEL) // Buttons are directly attached using keypad - #define BTN_EN1 61 - #define BTN_EN2 59 - #define BTN_ENC 43 + #define BTN_EN1 61 + #define BTN_EN2 59 + #define BTN_ENC 43 #else // Buttons attached to shift register of reprapworld keypad v1.1 - #define SHIFT_CLK 63 - #define SHIFT_LD 42 - #define SHIFT_OUT 17 - #define SHIFT_EN 17 + #define SHIFT_CLK 63 + #define SHIFT_LD 42 + #define SHIFT_OUT 17 + #define SHIFT_EN 17 #endif #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index fe0f4826be..78dd88809f 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -40,132 +40,132 @@ // // Servos // -#define SERVO0_PIN 46 // AUX3-6 -#define SERVO1_PIN 47 // AUX3-5 -#define SERVO2_PIN 48 // AUX3-4 -#define SERVO3_PIN 49 // AUX3-3 +#define SERVO0_PIN 46 // AUX3-6 +#define SERVO1_PIN 47 // AUX3-5 +#define SERVO2_PIN 48 // AUX3-4 +#define SERVO3_PIN 49 // AUX3-3 // // Limit Switches // -#define X_MIN_PIN 37 // No INT -#define X_MAX_PIN 40 // No INT -#define Y_MIN_PIN 41 // No INT -#define Y_MAX_PIN 38 // No INT -#define Z_MIN_PIN 18 // No INT -#define Z_MAX_PIN 19 // No INT +#define X_MIN_PIN 37 // No INT +#define X_MAX_PIN 40 // No INT +#define Y_MIN_PIN 41 // No INT +#define Y_MAX_PIN 38 // No INT +#define Z_MIN_PIN 18 // No INT +#define Z_MAX_PIN 19 // No INT // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN 19 #endif // // Steppers // -#define X_STEP_PIN 58 -#define X_DIR_PIN 57 -#define X_ENABLE_PIN 59 +#define X_STEP_PIN 58 +#define X_DIR_PIN 57 +#define X_ENABLE_PIN 59 -#define Y_STEP_PIN 5 -#define Y_DIR_PIN 17 -#define Y_ENABLE_PIN 4 +#define Y_STEP_PIN 5 +#define Y_DIR_PIN 17 +#define Y_ENABLE_PIN 4 -#define Z_STEP_PIN 16 -#define Z_DIR_PIN 11 -#define Z_ENABLE_PIN 3 +#define Z_STEP_PIN 16 +#define Z_DIR_PIN 11 +#define Z_ENABLE_PIN 3 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 29 +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 29 -#define E1_STEP_PIN 25 -#define E1_DIR_PIN 24 -#define E1_ENABLE_PIN 26 +#define E1_STEP_PIN 25 +#define E1_DIR_PIN 24 +#define E1_ENABLE_PIN 26 -#define E2_STEP_PIN 22 -#define E2_DIR_PIN 60 -#define E2_ENABLE_PIN 23 +#define E2_STEP_PIN 22 +#define E2_DIR_PIN 60 +#define E2_ENABLE_PIN 23 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 11 // Analog Input + #define TEMP_0_PIN 11 // Analog Input #else - #define TEMP_0_PIN 15 // Analog Input + #define TEMP_0_PIN 15 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 10 // Analog Input + #define TEMP_1_PIN 10 // Analog Input #else - #define TEMP_1_PIN 13 // Analog Input + #define TEMP_1_PIN 13 // Analog Input #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 9 // Analog Input + #define TEMP_2_PIN 9 // Analog Input #else - #define TEMP_2_PIN 12 // Analog Input + #define TEMP_2_PIN 12 // Analog Input #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 8 // Analog Input + #define TEMP_BED_PIN 8 // Analog Input #else - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN 14 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 9 -#define HEATER_2_PIN 8 -#define HEATER_BED_PIN 10 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 9 +#define HEATER_2_PIN 8 +#define HEATER_BED_PIN 10 #ifndef FAN_PIN - #define FAN_PIN 6 + #define FAN_PIN 6 #endif -#define FAN1_PIN 7 +#define FAN1_PIN 7 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 45 // Try the keypad connector +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 +#define CASE_LIGHT_PIN 45 // Try the keypad connector // // LCD / Controller // -#define BEEPER_PIN 61 +#define BEEPER_PIN 61 -#define BTN_EN1 44 -#define BTN_EN2 45 -#define BTN_ENC 33 +#define BTN_EN1 44 +#define BTN_EN2 45 +#define BTN_ENC 33 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 56 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock - #define SD_DETECT_PIN 35 + #define LCD_PINS_RS 56 // CS chip select / SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock + #define SD_DETECT_PIN 35 #else - #define LCD_PINS_RS 32 - #define LCD_PINS_ENABLE 31 - #define LCD_PINS_D4 14 - #define LCD_PINS_D5 30 - #define LCD_PINS_D6 39 - #define LCD_PINS_D7 15 + #define LCD_PINS_RS 32 + #define LCD_PINS_ENABLE 31 + #define LCD_PINS_D4 14 + #define LCD_PINS_D5 30 + #define LCD_PINS_D6 39 + #define LCD_PINS_D7 15 - #define SHIFT_CLK 43 - #define SHIFT_LD 35 - #define SHIFT_OUT 34 - #define SHIFT_EN 44 + #define SHIFT_CLK 43 + #define SHIFT_LD 35 + #define SHIFT_OUT 34 + #define SHIFT_EN 44 #if MB(MEGATRONICS_31, MEGATRONICS_32) - #define SD_DETECT_PIN 56 + #define SD_DETECT_PIN 56 #endif #endif @@ -173,23 +173,23 @@ // // M3/M4/M5 - Spindle/Laser Control // -#if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 43 // Pullup! - #define SPINDLE_DIR_PIN 42 +#if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 43 // Pullup! + #define SPINDLE_DIR_PIN 42 #elif EXTRUDERS <= 2 // Hijack the last extruder so that we can get the PWM signal off the Y breakout // Move Y to the E2 plug. This makes dual Y steppers harder - #undef Y_ENABLE_PIN // 4 - #undef Y_STEP_PIN // 5 - #undef Y_DIR_PIN // 17 - #undef E2_ENABLE_PIN // 23 - #undef E2_STEP_PIN // 22 - #undef E2_DIR_PIN // 60 - #define Y_ENABLE_PIN 23 - #define Y_STEP_PIN 22 - #define Y_DIR_PIN 60 - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 17 // Pullup! - #define SPINDLE_DIR_PIN 5 + #undef Y_ENABLE_PIN // 4 + #undef Y_STEP_PIN // 5 + #undef Y_DIR_PIN // 17 + #undef E2_ENABLE_PIN // 23 + #undef E2_STEP_PIN // 22 + #undef E2_DIR_PIN // 60 + #define Y_ENABLE_PIN 23 + #define Y_STEP_PIN 22 + #define Y_DIR_PIN 60 + #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 17 // Pullup! + #define SPINDLE_DIR_PIN 5 #endif diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 6d3102172b..3282216819 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -47,60 +47,60 @@ // // Servos // -#define SERVO0_PIN 36 // C1 (1280-EX1) -#define SERVO1_PIN 37 // C0 (1280-EX2) -#define SERVO2_PIN 40 // G1 (1280-EX3) -#define SERVO3_PIN 41 // G0 (1280-EX4) +#define SERVO0_PIN 36 // C1 (1280-EX1) +#define SERVO1_PIN 37 // C0 (1280-EX2) +#define SERVO2_PIN 40 // G1 (1280-EX3) +#define SERVO3_PIN 41 // G0 (1280-EX4) // // Limit Switches // -#define X_MIN_PIN 49 // L0 -#define X_MAX_PIN 48 // L1 -#define Y_MIN_PIN 47 // L2 -#define Y_MAX_PIN 46 // L3 -#define Z_MIN_PIN 43 // L6 -#define Z_MAX_PIN 42 // L7 +#define X_MIN_PIN 49 // L0 +#define X_MAX_PIN 48 // L1 +#define Y_MIN_PIN 47 // L2 +#define Y_MAX_PIN 46 // L3 +#define Z_MIN_PIN 43 // L6 +#define Z_MAX_PIN 42 // L7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 42 + #define Z_MIN_PROBE_PIN 42 #endif // // Filament Runout Pins // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 49 + #define FIL_RUNOUT_PIN 49 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN 47 + #define FIL_RUNOUT2_PIN 47 #endif // // Steppers // -#define X_STEP_PIN 55 // F1 -#define X_DIR_PIN 54 // F0 -#define X_ENABLE_PIN 56 // F2 +#define X_STEP_PIN 55 // F1 +#define X_DIR_PIN 54 // F0 +#define X_ENABLE_PIN 56 // F2 -#define Y_STEP_PIN 59 // F5 -#define Y_DIR_PIN 58 // F4 -#define Y_ENABLE_PIN 60 // F6 +#define Y_STEP_PIN 59 // F5 +#define Y_DIR_PIN 58 // F4 +#define Y_ENABLE_PIN 60 // F6 -#define Z_STEP_PIN 63 // K1 -#define Z_DIR_PIN 62 // K0 -#define Z_ENABLE_PIN 64 // K2 +#define Z_STEP_PIN 63 // K1 +#define Z_DIR_PIN 62 // K0 +#define Z_ENABLE_PIN 64 // K2 -#define E0_STEP_PIN 25 // A3 -#define E0_DIR_PIN 24 // A2 -#define E0_ENABLE_PIN 26 // A4 +#define E0_STEP_PIN 25 // A3 +#define E0_DIR_PIN 24 // A2 +#define E0_ENABLE_PIN 26 // A4 -#define E1_STEP_PIN 29 // A7 -#define E1_DIR_PIN 28 // A6 -#define E1_ENABLE_PIN 39 // G2 +#define E1_STEP_PIN 29 // A7 +#define E1_DIR_PIN 28 // A6 +#define E1_ENABLE_PIN 39 // G2 // // I2C Digipots - MCP4018 @@ -108,22 +108,22 @@ // Set from 0 - 127 with stop bit. // (Ex. 3F << 1 | 1) // -#define DIGIPOTS_I2C_SCL 76 // J5 -#define DIGIPOTS_I2C_SDA_X 57 // F3 -#define DIGIPOTS_I2C_SDA_Y 61 // F7 -#define DIGIPOTS_I2C_SDA_Z 65 // K3 -#define DIGIPOTS_I2C_SDA_E0 27 // A5 -#define DIGIPOTS_I2C_SDA_E1 77 // J6 +#define DIGIPOTS_I2C_SCL 76 // J5 +#define DIGIPOTS_I2C_SDA_X 57 // F3 +#define DIGIPOTS_I2C_SDA_Y 61 // F7 +#define DIGIPOTS_I2C_SDA_Z 65 // K3 +#define DIGIPOTS_I2C_SDA_E0 27 // A5 +#define DIGIPOTS_I2C_SDA_E1 77 // J6 #ifndef DIGIPOT_I2C_ADDRESS_A - #define DIGIPOT_I2C_ADDRESS_A 0x2F // unshifted slave address (5E <- 2F << 1) + #define DIGIPOT_I2C_ADDRESS_A 0x2F // unshifted slave address (5E <- 2F << 1) #endif // // Temperature Sensors // // K7 - 69 / ADC15 - 15 -#define TEMP_BED_PIN 15 +#define TEMP_BED_PIN 15 // SPI for Max6675 or Max31855 Thermocouple // Uses a separate SPI bus @@ -133,15 +133,15 @@ // 2 E4 CS2 // 78 E2 SCK // -#define THERMO_SCK_PIN 78 // E2 -#define THERMO_DO_PIN 3 // E5 -#define THERMO_CS1_PIN 5 // E3 -#define THERMO_CS2_PIN 2 // E4 +#define THERMO_SCK_PIN 78 // E2 +#define THERMO_DO_PIN 3 // E5 +#define THERMO_CS1_PIN 5 // E3 +#define THERMO_CS2_PIN 2 // E4 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#define MAX6675_SS_PIN THERMO_CS1_PIN +#define MAX6675_SS2_PIN THERMO_CS2_PIN +#define MAX6675_SCK_PIN THERMO_SCK_PIN +#define MAX6675_DO_PIN THERMO_DO_PIN // // Augmentation for auto-assigning plugs @@ -152,12 +152,12 @@ // // Labels from the schematic: -#define EX1_HEAT_PIN 6 // H3 -#define EX1_FAN_PIN 7 // H4 -#define EX2_HEAT_PIN 11 // B5 -#define EX2_FAN_PIN 12 // B6 -#define HBP_PIN 45 // L4 -#define EXTRA_FET_PIN 44 // L5 +#define EX1_HEAT_PIN 6 // H3 +#define EX1_FAN_PIN 7 // H4 +#define EX2_HEAT_PIN 11 // B5 +#define EX2_FAN_PIN 12 // B6 +#define HBP_PIN 45 // L4 +#define EXTRA_FET_PIN 44 // L5 #if HOTENDS > 1 #if TEMP_SENSOR_BED @@ -174,35 +174,35 @@ // // Heaters / Fans (24V) // -#define HEATER_0_PIN EX1_HEAT_PIN +#define HEATER_0_PIN EX1_HEAT_PIN -#if ENABLED(IS_EFB) // Hotend, Fan, Bed - #define HEATER_BED_PIN HBP_PIN -#elif ENABLED(IS_EEF) // Hotend, Hotend, Fan - #define HEATER_1_PIN EX2_HEAT_PIN -#elif ENABLED(IS_EEB) // Hotend, Hotend, Bed - #define HEATER_1_PIN EX2_HEAT_PIN - #define HEATER_BED_PIN HBP_PIN -#elif ENABLED(IS_EFF) // Hotend, Fan, Fan - #define FAN1_PIN HBP_PIN +#if ENABLED(IS_EFB) // Hotend, Fan, Bed + #define HEATER_BED_PIN HBP_PIN +#elif ENABLED(IS_EEF) // Hotend, Hotend, Fan + #define HEATER_1_PIN EX2_HEAT_PIN +#elif ENABLED(IS_EEB) // Hotend, Hotend, Bed + #define HEATER_1_PIN EX2_HEAT_PIN + #define HEATER_BED_PIN HBP_PIN +#elif ENABLED(IS_EFF) // Hotend, Fan, Fan + #define FAN1_PIN HBP_PIN #endif #ifndef FAN_PIN #if EITHER(IS_EFB, IS_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN EX2_HEAT_PIN + #define FAN_PIN EX2_HEAT_PIN #elif EITHER(IS_EEF, IS_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN HBP_PIN + #define FAN_PIN HBP_PIN #else - #define FAN_PIN EXTRA_FET_PIN + #define FAN_PIN EXTRA_FET_PIN #endif #endif // // Misc. Functions // -#define LED_PIN 13 // B7 -#define CUTOFF_RESET_PIN 16 // H1 -#define CUTOFF_TEST_PIN 17 // H0 +#define LED_PIN 13 // B7 +#define CUTOFF_RESET_PIN 16 // H1 +#define CUTOFF_TEST_PIN 17 // H0 // // LCD / Controller @@ -211,57 +211,57 @@ #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS 33 // C4: LCD-STROBE - #define LCD_PINS_ENABLE 72 // J2: LEFT - #define LCD_PINS_D4 35 // C2: LCD-CLK - #define LCD_PINS_D5 32 // C5: RLED - #define LCD_PINS_D6 34 // C3: LCD-DATA - #define LCD_PINS_D7 31 // C6: GLED + #define LCD_PINS_RS 33 // C4: LCD-STROBE + #define LCD_PINS_ENABLE 72 // J2: LEFT + #define LCD_PINS_D4 35 // C2: LCD-CLK + #define LCD_PINS_D5 32 // C5: RLED + #define LCD_PINS_D6 34 // C3: LCD-DATA + #define LCD_PINS_D7 31 // C6: GLED - #define BTN_EN2 75 // J4, UP - #define BTN_EN1 73 // J3, DOWN + #define BTN_EN2 75 // J4, UP + #define BTN_EN1 73 // J3, DOWN //STOP button connected as KILL_PIN - #define KILL_PIN 14 // J1, RIGHT + #define KILL_PIN 14 // J1, RIGHT //KILL - not connected - #define BEEPER_PIN 8 // H5, SD_WP + #define BEEPER_PIN 8 // H5, SD_WP //on board leds - #define STAT_LED_RED_LED SERVO0_PIN // C1 (1280-EX1, DEBUG2) - #define STAT_LED_BLUE_PIN SERVO1_PIN // C0 (1280-EX2, DEBUG3) + #define STAT_LED_RED_LED SERVO0_PIN // C1 (1280-EX1, DEBUG2) + #define STAT_LED_BLUE_PIN SERVO1_PIN // C0 (1280-EX2, DEBUG3) #else // Replicator uses a 3-wire SR controller with HD44780 - #define SR_DATA_PIN 34 // C3 - #define SR_CLK_PIN 35 // C2 - #define SR_STROBE_PIN 33 // C4 + #define SR_DATA_PIN 34 // C3 + #define SR_CLK_PIN 35 // C2 + #define SR_STROBE_PIN 33 // C4 - #define BTN_UP 75 // J4 - #define BTN_DWN 73 // J3 - #define BTN_LFT 72 // J2 - #define BTN_RT 14 // J1 + #define BTN_UP 75 // J4 + #define BTN_DWN 73 // J3 + #define BTN_LFT 72 // J2 + #define BTN_RT 14 // J1 // Disable encoder #undef BTN_EN1 #undef BTN_EN2 - #define BEEPER_PIN 4 // G5 + #define BEEPER_PIN 4 // G5 - #define STAT_LED_RED_PIN 32 // C5 - #define STAT_LED_BLUE_PIN 31 // C6 (Actually green) + #define STAT_LED_RED_PIN 32 // C5 + #define STAT_LED_BLUE_PIN 31 // C6 (Actually green) #endif - #define BTN_CENTER 15 // J0 - #define BTN_ENC BTN_CENTER + #define BTN_CENTER 15 // J0 + #define BTN_ENC BTN_CENTER #endif // HAS_SPI_LCD // // SD Card // -#define SDSS 53 // B0 -#define SD_DETECT_PIN 9 // H6 +#define SDSS 53 // B0 +#define SD_DETECT_PIN 9 // H6 // // TMC 220x @@ -280,19 +280,19 @@ * Software serial */ - #define X_SERIAL_TX_PIN 16 - #define X_SERIAL_RX_PIN 17 + #define X_SERIAL_TX_PIN 16 + #define X_SERIAL_RX_PIN 17 - #define Y_SERIAL_TX_PIN 18 - #define Y_SERIAL_RX_PIN 19 + #define Y_SERIAL_TX_PIN 18 + #define Y_SERIAL_RX_PIN 19 - #define Z_SERIAL_TX_PIN 41 - #define Z_SERIAL_RX_PIN 66 + #define Z_SERIAL_TX_PIN 41 + #define Z_SERIAL_RX_PIN 66 - #define E0_SERIAL_TX_PIN 40 - #define E0_SERIAL_RX_PIN 67 + #define E0_SERIAL_TX_PIN 40 + #define E0_SERIAL_RX_PIN 67 - #define E1_SERIAL_TX_PIN 37 - #define E1_SERIAL_RX_PIN 68 + #define E1_SERIAL_TX_PIN 37 + #define E1_SERIAL_RX_PIN 68 #endif diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index 5b06e3b835..35d1b59ecb 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -42,102 +42,102 @@ // // Limit Switches // -#define X_MIN_PIN 5 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 2 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 6 -#define Z_MAX_PIN -1 +#define X_MIN_PIN 5 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 2 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 6 +#define Z_MAX_PIN -1 // // Steppers // -#define X_STEP_PIN 48 -#define X_DIR_PIN 47 -#define X_ENABLE_PIN 49 +#define X_STEP_PIN 48 +#define X_DIR_PIN 47 +#define X_ENABLE_PIN 49 -#define Y_STEP_PIN 39 // A6 -#define Y_DIR_PIN 40 // A0 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 39 // A6 +#define Y_DIR_PIN 40 // A0 +#define Y_ENABLE_PIN 38 -#define Z_STEP_PIN 42 // A2 -#define Z_DIR_PIN 43 // A6 -#define Z_ENABLE_PIN 41 // A1 +#define Z_STEP_PIN 42 // A2 +#define Z_DIR_PIN 43 // A6 +#define Z_ENABLE_PIN 41 // A1 -#define E0_STEP_PIN 45 -#define E0_DIR_PIN 44 -#define E0_ENABLE_PIN 27 +#define E0_STEP_PIN 45 +#define E0_DIR_PIN 44 +#define E0_ENABLE_PIN 27 -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 35 -#define E1_ENABLE_PIN 37 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 35 +#define E1_ENABLE_PIN 37 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input -#define TEMP_1_PIN 6 // Analog Input -#define TEMP_BED_PIN 6 // Analog Input +#define TEMP_0_PIN 7 // Analog Input +#define TEMP_1_PIN 6 // Analog Input +#define TEMP_BED_PIN 6 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 7 // EXTRUDER 1 -#define HEATER_1_PIN 8 // EXTRUDER 2 -#define HEATER_BED_PIN 3 // BED +#define HEATER_0_PIN 7 // EXTRUDER 1 +#define HEATER_1_PIN 8 // EXTRUDER 2 +#define HEATER_BED_PIN 3 // BED #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN 9 #endif // // Misc. Functions // -#define SDSS 16 -#define LED_PIN 46 +#define SDSS 16 +#define LED_PIN 46 // // LCD / Controller // -#define BEEPER_PIN -1 +#define BEEPER_PIN -1 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 15 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 11 // SID (MOSI) - #define LCD_PINS_D4 10 // SCK (CLK) clock + #define LCD_PINS_RS 15 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 11 // SID (MOSI) + #define LCD_PINS_D4 10 // SCK (CLK) clock - #define BTN_EN1 18 - #define BTN_EN2 17 - #define BTN_ENC 25 + #define BTN_EN1 18 + #define BTN_EN2 17 + #define BTN_ENC 25 - #define SD_DETECT_PIN 30 + #define SD_DETECT_PIN 30 #else - #define LCD_PINS_RS -1 - #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 + #define LCD_PINS_ENABLE -1 // Buttons are directly attached using keypad - #define BTN_EN1 -1 - #define BTN_EN2 -1 - #define BTN_ENC -1 + #define BTN_EN1 -1 + #define BTN_EN2 -1 + #define BTN_ENC -1 - #define SD_DETECT_PIN -1 // Minitronics doesn't use this + #define SD_DETECT_PIN -1 // Minitronics doesn't use this #endif // // M3/M4/M5 - Spindle/Laser Control // -#if HAS_CUTTER // assumes we're only doing CNC work (no 3D printing) +#if HAS_CUTTER // assumes we're only doing CNC work (no 3D printing) #undef HEATER_BED_PIN - #undef TEMP_BED_PIN // need to free up some pins but also need to - #undef TEMP_0_PIN // re-assign them (to unused pins) because Marlin - #undef TEMP_1_PIN // requires the presence of certain pins or else it - #define HEATER_BED_PIN 4 // won't compile - #define TEMP_BED_PIN 50 - #define TEMP_0_PIN 51 - #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup - #define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage - #define SPINDLE_DIR_PIN 53 + #undef TEMP_BED_PIN // need to free up some pins but also need to + #undef TEMP_0_PIN // re-assign them (to unused pins) because Marlin + #undef TEMP_1_PIN // requires the presence of certain pins or else it + #define HEATER_BED_PIN 4 // won't compile + #define TEMP_BED_PIN 50 + #define TEMP_0_PIN 51 + #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup + #define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage + #define SPINDLE_DIR_PIN 53 #endif diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 80f72d04e9..4e02127c12 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -37,83 +37,83 @@ // // Limit Switches // -#define X_STOP_PIN 24 -#define Y_STOP_PIN 28 -#define Z_MIN_PIN 46 -#define Z_MAX_PIN 32 +#define X_STOP_PIN 24 +#define Y_STOP_PIN 28 +#define Z_MIN_PIN 46 +#define Z_MAX_PIN 32 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 46 // JP4, Tfeed1 + #define Z_MIN_PROBE_PIN 46 // JP4, Tfeed1 #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) - #define FIL_RUNOUT_PIN 44 // JP3, Tfeed2 + #define FIL_RUNOUT_PIN 44 // JP3, Tfeed2 #endif // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN 37 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 35 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN 43 +#define E0_DIR_PIN 45 +#define E0_ENABLE_PIN 41 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input - Redundant temp sensor -#define TEMP_2_PIN 12 // Analog Input -#define TEMP_3_PIN 14 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 9 // Analog Input - Redundant temp sensor +#define TEMP_2_PIN 12 // Analog Input +#define TEMP_3_PIN 14 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 -#define FAN_PIN 7 // material cooling fan +#define FAN_PIN 7 // material cooling fan // // SD Card // -#define SDSS 53 -#define SD_DETECT_PIN 38 +#define SDSS 53 +#define SD_DETECT_PIN 38 // // Misc. Functions // -#define LED_PIN 13 // On PCB status led -#define PS_ON_PIN 12 // For stepper/heater/fan power. Active HIGH. -#define POWER_LOSS_PIN 34 // Power check - whether hotends/steppers/fans have power +#define LED_PIN 13 // On PCB status led +#define PS_ON_PIN 12 // For stepper/heater/fan power. Active HIGH. +#define POWER_LOSS_PIN 34 // Power check - whether hotends/steppers/fans have power #if ENABLED(BATTERY_STATUS_AVAILABLE) #undef BATTERY_STATUS_PIN - #define BATTERY_STATUS_PIN 26 // Status of power loss battery, whether it is charged (low) or charging (high) + #define BATTERY_STATUS_PIN 26 // Status of power loss battery, whether it is charged (low) or charging (high) #endif #if ENABLED(INPUT_VOLTAGE_AVAILABLE) #undef VOLTAGE_DETECTION_PIN - #define VOLTAGE_DETECTION_PIN 11 // Analog Input - ADC Voltage level of main input + #define VOLTAGE_DETECTION_PIN 11 // Analog Input - ADC Voltage level of main input #endif // @@ -121,24 +121,24 @@ // #if HAS_GRAPHICAL_LCD // OVERLORD OLED pins - #define LCD_PINS_RS 20 - #define LCD_PINS_D5 21 - #define LCD_PINS_ENABLE 15 - #define LCD_PINS_D4 14 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_RS 20 + #define LCD_PINS_D5 21 + #define LCD_PINS_ENABLE 15 + #define LCD_PINS_D4 14 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 #ifndef LCD_RESET_PIN - #define LCD_RESET_PIN 5 // LCD_PINS_D6 + #define LCD_RESET_PIN 5 // LCD_PINS_D6 #endif #endif #if ENABLED(NEWPANEL) - #define BTN_ENC 16 // Enter Pin - #define BTN_UP 19 // Button UP Pin - #define BTN_DWN 17 // Button DOWN Pin + #define BTN_ENC 16 // Enter Pin + #define BTN_UP 19 // Button UP Pin + #define BTN_DWN 17 // Button DOWN Pin #endif // Additional connectors/pins on the Overlord V1.X board -#define PCB_VERSION_PIN 22 -#define APPROACH_PIN 11 // JP7, Tpd -#define GATE_PIN 36 // Threshold, JP6, Tg +#define PCB_VERSION_PIN 22 +#define APPROACH_PIN 11 // JP7, Tpd +#define GATE_PIN 36 // Threshold, JP6, Tg diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 4c618bda4e..f00d817d6e 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -49,95 +49,95 @@ // // Limit Switches // -#define X_MIN_PIN 14 -#define X_MAX_PIN 15 -#define Y_MIN_PIN 16 -#define Y_MAX_PIN 17 -#define Z_MIN_PIN 23 -#define Z_MAX_PIN 22 +#define X_MIN_PIN 14 +#define X_MAX_PIN 15 +#define Y_MIN_PIN 16 +#define Y_MAX_PIN 17 +#define Z_MIN_PIN 23 +#define Z_MAX_PIN 22 // // Steppers // -#define X_STEP_PIN 55 -#define X_DIR_PIN 54 -#define X_ENABLE_PIN 60 +#define X_STEP_PIN 55 +#define X_DIR_PIN 54 +#define X_ENABLE_PIN 60 -#define Y_STEP_PIN 57 -#define Y_DIR_PIN 56 -#define Y_ENABLE_PIN 61 +#define Y_STEP_PIN 57 +#define Y_DIR_PIN 56 +#define Y_ENABLE_PIN 61 -#define Z_STEP_PIN 59 -#define Z_DIR_PIN 58 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 59 +#define Z_DIR_PIN 58 +#define Z_ENABLE_PIN 62 -#define E0_STEP_PIN 67 -#define E0_DIR_PIN 24 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN 67 +#define E0_DIR_PIN 24 +#define E0_ENABLE_PIN 26 // // Temperature Sensors // -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN 10 -#define TEMP_BED_PIN 10 -#define TEMP_2_PIN 11 -#define TEMP_3_PIN 12 +#define TEMP_0_PIN 9 // Analog Input +#define TEMP_1_PIN 10 +#define TEMP_BED_PIN 10 +#define TEMP_2_PIN 11 +#define TEMP_3_PIN 12 // // Heaters / Fans // #ifndef HEATER_0_PIN - #define HEATER_0_PIN 10 // E0 + #define HEATER_0_PIN 10 // E0 #endif #ifndef HEATER_1_PIN - #define HEATER_1_PIN 2 // E1 + #define HEATER_1_PIN 2 // E1 #endif -#define HEATER_BED_PIN 8 // HEAT-BED +#define HEATER_BED_PIN 8 // HEAT-BED #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN 9 #endif #ifndef FAN_2_PIN - #define FAN_2_PIN 7 + #define FAN_2_PIN 7 #endif -#define SDPOWER_PIN -1 -#define LED_PIN -1 -#define PS_ON_PIN -1 -#define KILL_PIN -1 +#define SDPOWER_PIN -1 +#define LED_PIN -1 +#define PS_ON_PIN -1 +#define KILL_PIN -1 -#define SSR_PIN 6 +#define SSR_PIN 6 // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // // SD Support // -#define SD_DETECT_PIN 49 -#define SDSS 53 +#define SD_DETECT_PIN 49 +#define SDSS 53 // // LCD / Controller // -#define BEEPER_PIN 29 +#define BEEPER_PIN 29 #if HAS_SPI_LCD - #define LCD_PINS_RS 33 - #define LCD_PINS_ENABLE 30 - #define LCD_PINS_D4 35 - #define LCD_PINS_D5 32 - #define LCD_PINS_D6 37 - #define LCD_PINS_D7 36 + #define LCD_PINS_RS 33 + #define LCD_PINS_ENABLE 30 + #define LCD_PINS_D4 35 + #define LCD_PINS_D5 32 + #define LCD_PINS_D6 37 + #define LCD_PINS_D7 36 - #define BTN_EN1 47 - #define BTN_EN2 48 - #define BTN_ENC 31 + #define BTN_EN1 47 + #define BTN_EN2 48 + #define BTN_ENC 31 - #define LCD_SDSS 53 + #define LCD_SDSS 53 #endif diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index 88fa1ada29..34861277a8 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -20,9 +20,9 @@ * */ -#define HEATER_0_PIN 9 // E0 -#define HEATER_1_PIN 10 // E1 -#define FAN_PIN 11 -#define FAN2_PIN 12 +#define HEATER_0_PIN 9 // E0 +#define HEATER_1_PIN 10 // E1 +#define FAN_PIN 11 +#define FAN2_PIN 12 #include "pins_PICA.h" diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index bde1f87088..4c79507eab 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -27,67 +27,67 @@ #define BOARD_INFO_NAME "Silver Gate" -#define X_STEP_PIN 43 -#define X_DIR_PIN 44 -#define X_ENABLE_PIN 42 -#define X_MIN_PIN 31 -#define X_MAX_PIN 34 +#define X_STEP_PIN 43 +#define X_DIR_PIN 44 +#define X_ENABLE_PIN 42 +#define X_MIN_PIN 31 +#define X_MAX_PIN 34 -#define Y_STEP_PIN 40 -#define Y_DIR_PIN 41 -#define Y_ENABLE_PIN 39 -#define Y_MIN_PIN 32 -#define Y_MAX_PIN 35 +#define Y_STEP_PIN 40 +#define Y_DIR_PIN 41 +#define Y_ENABLE_PIN 39 +#define Y_MIN_PIN 32 +#define Y_MAX_PIN 35 -#define Z_STEP_PIN 13 -#define Z_DIR_PIN 38 -#define Z_ENABLE_PIN 14 -#define Z_MIN_PIN 33 -#define Z_MAX_PIN 36 +#define Z_STEP_PIN 13 +#define Z_DIR_PIN 38 +#define Z_ENABLE_PIN 14 +#define Z_MIN_PIN 33 +#define Z_MAX_PIN 36 -#define E0_STEP_PIN 27 -#define E0_DIR_PIN 37 -#define E0_ENABLE_PIN 45 +#define E0_STEP_PIN 27 +#define E0_DIR_PIN 37 +#define E0_ENABLE_PIN 45 -#define SDSS 16 +#define SDSS 16 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 34 // X_MAX unless overridden + #define FIL_RUNOUT_PIN 34 // X_MAX unless overridden #endif #ifndef FAN_PIN - #define FAN_PIN 5 + #define FAN_PIN 5 #endif -#define HEATER_0_PIN 7 +#define HEATER_0_PIN 7 -#define ORIG_E0_AUTO_FAN_PIN 3 // Use this by NOT overriding E0_AUTO_FAN_PIN -#define CONTROLLER_FAN_PIN 2 +#define ORIG_E0_AUTO_FAN_PIN 3 // Use this by NOT overriding E0_AUTO_FAN_PIN +#define CONTROLLER_FAN_PIN 2 -#define TEMP_0_PIN 7 // Analog Input +#define TEMP_0_PIN 7 // Analog Input -#define HEATER_BED_PIN 8 -#define TEMP_BED_PIN 6 +#define HEATER_BED_PIN 8 +#define TEMP_BED_PIN 6 #if HAS_GRAPHICAL_LCD - #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 - #define LCD_PINS_RS 30 - #define LCD_PINS_ENABLE 20 - #define LCD_PINS_D4 25 - #define BEEPER_PIN 29 - #define BTN_EN1 19 - #define BTN_EN2 22 - #define BTN_ENC 24 - #define LCD_BACKLIGHT_PIN 6 + #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 + #define LCD_PINS_RS 30 + #define LCD_PINS_ENABLE 20 + #define LCD_PINS_D4 25 + #define BEEPER_PIN 29 + #define BTN_EN1 19 + #define BTN_EN2 22 + #define BTN_ENC 24 + #define LCD_BACKLIGHT_PIN 6 #if ENABLED(SILVER_GATE_GLCD_CONTROLLER) - #define KILL_PIN 21 - #define HOME_PIN 28 + #define KILL_PIN 21 + #define HOME_PIN 28 #endif #endif #endif -#define SD_DETECT_PIN 15 +#define SD_DETECT_PIN 15 -#define STAT_LED_RED_PIN 23 -#define STAT_LED_BLUE_PIN 26 -#define CASE_LIGHT_PIN 51 +#define STAT_LED_RED_PIN 23 +#define STAT_LED_BLUE_PIN 26 +#define CASE_LIGHT_PIN 51 diff --git a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h index c011d9daa7..6c53b7ea4e 100644 --- a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h +++ b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h @@ -36,76 +36,76 @@ // // Limit Switches // -#define X_STOP_PIN 19 -#define Y_STOP_PIN 18 -#define Z_STOP_PIN 38 +#define X_STOP_PIN 19 +#define Y_STOP_PIN 18 +#define Z_STOP_PIN 38 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 38 + #define Z_MIN_PROBE_PIN 38 #endif // // Steppers // -#define X_STEP_PIN 22 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 57 +#define X_STEP_PIN 22 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 57 -#define Y_STEP_PIN 25 -#define Y_DIR_PIN 26 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 25 +#define Y_DIR_PIN 26 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 29 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 28 +#define Z_STEP_PIN 29 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 28 -#define E0_STEP_PIN 55 -#define E0_DIR_PIN 56 -#define E0_ENABLE_PIN 54 +#define E0_STEP_PIN 55 +#define E0_DIR_PIN 56 +#define E0_ENABLE_PIN 54 // // Temperature Sensors // -#define TEMP_0_PIN 13 -#define TEMP_BED_PIN 14 +#define TEMP_0_PIN 13 +#define TEMP_BED_PIN 14 // // Heaters / Fans // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 44 -#define FAN_PIN 12 // IO pin. Buffer needed +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 44 +#define FAN_PIN 12 // IO pin. Buffer needed // // SD Card // -#define SD_DETECT_PIN -1 -#define SDSS 53 +#define SD_DETECT_PIN -1 +#define SDSS 53 // // Misc. Functions // -#define BEEPER_PIN 37 -#define KILL_PIN 64 +#define BEEPER_PIN 37 +#define KILL_PIN 64 // // LCD / Controller (Integrated MINIPANEL) // #if ENABLED(MINIPANEL) - #define DOGLCD_A0 40 - #define DOGLCD_CS 41 - #define LCD_BACKLIGHT_PIN 65 // Backlight LED on A11/D65 - #define LCD_RESET_PIN 27 + #define DOGLCD_A0 40 + #define DOGLCD_CS 41 + #define LCD_BACKLIGHT_PIN 65 // Backlight LED on A11/D65 + #define LCD_RESET_PIN 27 - #define BTN_EN1 2 - #define BTN_EN2 3 - #define BTN_ENC 5 + #define BTN_EN1 2 + #define BTN_EN2 3 + #define BTN_ENC 5 // This display has adjustable contrast - #define LCD_CONTRAST_MIN 0 - #define LCD_CONTRAST_MAX 255 - #define LCD_CONTRAST_INIT LCD_CONTRAST_MAX + #define LCD_CONTRAST_MIN 0 + #define LCD_CONTRAST_MAX 255 + #define LCD_CONTRAST_INIT LCD_CONTRAST_MAX #endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 4cfa326165..430fa170e1 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -39,10 +39,10 @@ #endif // TMC2130 Diag Pins (currently just for reference) -#define X_DIAG_PIN 64 -#define Y_DIAG_PIN 69 -#define Z_DIAG_PIN 68 -#define E0_DIAG_PIN 65 +#define X_DIAG_PIN 64 +#define Y_DIAG_PIN 69 +#define Z_DIAG_PIN 68 +#define E0_DIAG_PIN 65 // // Limit Switches @@ -55,20 +55,20 @@ #if DISABLED(SENSORLESS_HOMING) - #define X_STOP_PIN 12 - #define Y_STOP_PIN 11 - #define Z_STOP_PIN 10 + #define X_STOP_PIN 12 + #define Y_STOP_PIN 11 + #define Z_STOP_PIN 10 #else - #define X_STOP_PIN X_DIAG_PIN - #define Y_STOP_PIN Y_DIAG_PIN + #define X_STOP_PIN X_DIAG_PIN + #define Y_STOP_PIN Y_DIAG_PIN #if ENABLED(BLTOUCH) - #define Z_STOP_PIN 11 // Y-MIN - #define SERVO0_PIN 10 // Z-MIN + #define Z_STOP_PIN 11 // Y-MIN + #define SERVO0_PIN 10 // Z-MIN #else - #define Z_STOP_PIN 10 + #define Z_STOP_PIN 10 #endif #endif @@ -77,104 +77,104 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 + #define Z_MIN_PROBE_PIN 10 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 49 -#define X_ENABLE_PIN 29 -#define X_CS_PIN 41 +#define X_STEP_PIN 37 +#define X_DIR_PIN 49 +#define X_ENABLE_PIN 29 +#define X_CS_PIN 41 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 48 -#define Y_ENABLE_PIN 28 -#define Y_CS_PIN 39 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 48 +#define Y_ENABLE_PIN 28 +#define Y_CS_PIN 39 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 -#define Z_CS_PIN 67 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 +#define Z_CS_PIN 67 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_CS_PIN 66 +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 +#define E0_CS_PIN 66 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 3 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN 8 #endif #ifndef FAN1_PIN - #define FAN1_PIN 6 + #define FAN1_PIN 6 #endif // // Misc. Functions // -#define SDSS 77 -#define LED_PIN 13 -#define CASE_LIGHT_PIN 9 +#define SDSS 77 +#define LED_PIN 13 +#define CASE_LIGHT_PIN 9 // // M3/M4/M5 - Spindle/Laser Control // // use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 18 // Pullup! +#define SPINDLE_DIR_PIN 19 // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#define E_MUX0_PIN 17 +#define E_MUX1_PIN 16 +#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 // // LCD / Controller // #if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL - #define KILL_PIN 32 + #define KILL_PIN 32 #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 85 - #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 70 - #define BTN_EN1 61 - #define BTN_EN2 59 + #define LCD_PINS_RS 85 + #define LCD_PINS_ENABLE 71 + #define LCD_PINS_D4 70 + #define BTN_EN1 61 + #define BTN_EN2 59 #else - #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 61 - #define LCD_PINS_D4 59 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 - #define BTN_EN1 14 - #define BTN_EN2 72 + #define LCD_PINS_RS 82 + #define LCD_PINS_ENABLE 61 + #define LCD_PINS_D4 59 + #define LCD_PINS_D5 70 + #define LCD_PINS_D6 85 + #define LCD_PINS_D7 71 + #define BTN_EN1 14 + #define BTN_EN2 72 #endif - #define BTN_ENC 9 // AUX-2 - #define BEEPER_PIN 84 // AUX-4 - #define SD_DETECT_PIN 15 + #define BTN_ENC 9 // AUX-2 + #define BEEPER_PIN 84 // AUX-4 + #define SD_DETECT_PIN 15 #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 2bc577313e..6e8463d0bd 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -39,10 +39,10 @@ #endif // TMC2130 Diag Pins -#define X_DIAG_PIN 64 -#define Y_DIAG_PIN 69 -#define Z_DIAG_PIN 68 -#define E0_DIAG_PIN 65 +#define X_DIAG_PIN 64 +#define Y_DIAG_PIN 69 +#define Z_DIAG_PIN 68 +#define E0_DIAG_PIN 65 // // Limit Switches @@ -55,141 +55,141 @@ #if DISABLED(SENSORLESS_HOMING) - #define X_MIN_PIN 12 // X- - #define Y_MIN_PIN 11 // Y- - #define Z_MIN_PIN 10 // Z- - #define X_MAX_PIN 81 // X+ - #define Y_MAX_PIN 57 // Y+ + #define X_MIN_PIN 12 // X- + #define Y_MIN_PIN 11 // Y- + #define Z_MIN_PIN 10 // Z- + #define X_MAX_PIN 81 // X+ + #define Y_MAX_PIN 57 // Y+ #else #if X_HOME_DIR < 0 - #define X_MIN_PIN X_DIAG_PIN - #define X_MAX_PIN 81 // X+ + #define X_MIN_PIN X_DIAG_PIN + #define X_MAX_PIN 81 // X+ #else - #define X_MIN_PIN 12 // X- - #define X_MAX_PIN X_DIAG_PIN + #define X_MIN_PIN 12 // X- + #define X_MAX_PIN X_DIAG_PIN #endif #if Y_HOME_DIR < 0 - #define Y_MIN_PIN Y_DIAG_PIN - #define Y_MAX_PIN 57 // Y+ + #define Y_MIN_PIN Y_DIAG_PIN + #define Y_MAX_PIN 57 // Y+ #else - #define Y_MIN_PIN 11 // Y- - #define Y_MAX_PIN Y_DIAG_PIN + #define Y_MIN_PIN 11 // Y- + #define Y_MAX_PIN Y_DIAG_PIN #endif #if ENABLED(BLTOUCH) - #define Z_MIN_PIN 11 // Y-MIN - #define SERVO0_PIN 10 // Z-MIN + #define Z_MIN_PIN 11 // Y-MIN + #define SERVO0_PIN 10 // Z-MIN #else - #define Z_MIN_PIN 10 + #define Z_MIN_PIN 10 #endif #endif -#define Z_MAX_PIN 7 +#define Z_MAX_PIN 7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 + #define Z_MIN_PROBE_PIN 10 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 49 -#define X_ENABLE_PIN 29 -#define X_CS_PIN 41 +#define X_STEP_PIN 37 +#define X_DIR_PIN 49 +#define X_ENABLE_PIN 29 +#define X_CS_PIN 41 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 48 -#define Y_ENABLE_PIN 28 -#define Y_CS_PIN 39 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 48 +#define Y_ENABLE_PIN 28 +#define Y_CS_PIN 39 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 -#define Z_CS_PIN 67 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 +#define Z_CS_PIN 67 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_CS_PIN 66 +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 +#define E0_CS_PIN 66 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 3 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN 8 #endif -#define FAN1_PIN 6 +#define FAN1_PIN 6 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define CASE_LIGHT_PIN 9 +#define SDSS 53 +#define LED_PIN 13 +#define CASE_LIGHT_PIN 9 // // M3/M4/M5 - Spindle/Laser Control // // use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 18 // Pullup! +#define SPINDLE_DIR_PIN 19 // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#define E_MUX0_PIN 17 +#define E_MUX1_PIN 16 +#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 // // LCD / Controller // #if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) - #define KILL_PIN 32 + #define KILL_PIN 32 #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 85 - #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 70 - #define BTN_EN1 18 - #define BTN_EN2 19 + #define LCD_PINS_RS 85 + #define LCD_PINS_ENABLE 71 + #define LCD_PINS_D4 70 + #define BTN_EN1 18 + #define BTN_EN2 19 #else - #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 18 // On 0.6b, use 61 - #define LCD_PINS_D4 19 // On 0.6b, use 59 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 - #define BTN_EN1 14 - #define BTN_EN2 72 + #define LCD_PINS_RS 82 + #define LCD_PINS_ENABLE 18 // On 0.6b, use 61 + #define LCD_PINS_D4 19 // On 0.6b, use 59 + #define LCD_PINS_D5 70 + #define LCD_PINS_D6 85 + #define LCD_PINS_D7 71 + #define BTN_EN1 14 + #define BTN_EN2 72 #endif - #define BTN_ENC 9 // AUX-2 - #define BEEPER_PIN 84 // AUX-4 + #define BTN_ENC 9 // AUX-2 + #define BEEPER_PIN 84 // AUX-4 - #define SD_DETECT_PIN 15 + #define SD_DETECT_PIN 15 #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 50aec546a6..18bc3ddd16 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -38,104 +38,104 @@ // // Limit Switches // -#define X_MIN_PIN 12 -#define X_MAX_PIN 30 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 24 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 23 +#define X_MIN_PIN 12 +#define X_MAX_PIN 30 +#define Y_MIN_PIN 11 +#define Y_MAX_PIN 24 +#define Z_MIN_PIN 10 +#define Z_MAX_PIN 23 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 23 + #define Z_MIN_PROBE_PIN 23 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN 37 +#define X_DIR_PIN 48 +#define X_ENABLE_PIN 29 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 49 +#define Y_ENABLE_PIN 28 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 // Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 +#define X_MS1_PIN 40 +#define X_MS2_PIN 41 +#define Y_MS1_PIN 69 +#define Y_MS2_PIN 39 +#define Z_MS1_PIN 68 +#define Z_MS2_PIN 67 +#define E0_MS1_PIN 65 +#define E0_MS2_PIN 66 -#define MOTOR_CURRENT_PWM_XY_PIN 46 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 44 +#define MOTOR_CURRENT_PWM_XY_PIN 46 +#define MOTOR_CURRENT_PWM_Z_PIN 45 +#define MOTOR_CURRENT_PWM_E_PIN 44 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE - #define MOTOR_CURRENT_PWM_RANGE 2000 + #define MOTOR_CURRENT_PWM_RANGE 2000 #endif #define DEFAULT_PWM_MOTOR_CURRENT {1300, 1300, 1250} // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_1_PIN 7 +#define HEATER_0_PIN 3 +#define HEATER_1_PIN 7 #if !MB(MINIRAMBO_10A) - #define HEATER_2_PIN 6 + #define HEATER_2_PIN 6 #endif -#define HEATER_BED_PIN 4 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN 8 #endif -#define FAN1_PIN 6 +#define FAN1_PIN 6 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS 53 +#define LED_PIN 13 #if !MB(MINIRAMBO_10A) - #define CASE_LIGHT_PIN 9 + #define CASE_LIGHT_PIN 9 #endif // // M3/M4/M5 - Spindle/Laser Control // // use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 18 // Pullup! +#define SPINDLE_DIR_PIN 19 // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 +#define E_MUX0_PIN 17 +#define E_MUX1_PIN 16 #if !MB(MINIRAMBO_10A) - #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 + #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 #endif // @@ -144,46 +144,46 @@ #if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL #if !MB(MINIRAMBO_10A) - #define KILL_PIN 32 + #define KILL_PIN 32 #endif #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL #if MB(MINIRAMBO_10A) - #define BEEPER_PIN 78 + #define BEEPER_PIN 78 - #define BTN_EN1 80 - #define BTN_EN2 73 - #define BTN_ENC 21 + #define BTN_EN1 80 + #define BTN_EN2 73 + #define BTN_ENC 21 - #define LCD_PINS_RS 38 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 14 - #define LCD_PINS_D5 15 - #define LCD_PINS_D6 32 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS 38 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 14 + #define LCD_PINS_D5 15 + #define LCD_PINS_D6 32 + #define LCD_PINS_D7 31 - #define SD_DETECT_PIN 72 + #define SD_DETECT_PIN 72 - #else // !MINIRAMBO_10A + #else // !MINIRAMBO_10A // AUX-4 - #define BEEPER_PIN 84 + #define BEEPER_PIN 84 // AUX-2 - #define BTN_EN1 14 - #define BTN_EN2 72 - #define BTN_ENC 9 + #define BTN_EN1 14 + #define BTN_EN2 72 + #define BTN_ENC 9 - #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 18 - #define LCD_PINS_D4 19 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 + #define LCD_PINS_RS 82 + #define LCD_PINS_ENABLE 18 + #define LCD_PINS_D4 19 + #define LCD_PINS_D5 70 + #define LCD_PINS_D6 85 + #define LCD_PINS_D7 71 - #define SD_DETECT_PIN 15 + #define SD_DETECT_PIN 15 #endif // !MINIRAMBO_10A diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 2e52e9427c..0a443cc19a 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -50,64 +50,64 @@ // // Servos // -#define SERVO0_PIN 22 // Motor header MX1 -#define SERVO1_PIN 23 // Motor header MX2 -#define SERVO2_PIN 24 // Motor header MX3 -#define SERVO3_PIN 5 // PWM header pin 5 +#define SERVO0_PIN 22 // Motor header MX1 +#define SERVO1_PIN 23 // Motor header MX2 +#define SERVO2_PIN 24 // Motor header MX3 +#define SERVO3_PIN 5 // PWM header pin 5 // // Limit Switches // -#define X_MIN_PIN 12 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 23 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 30 +#define X_MIN_PIN 12 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 11 +#define Y_MAX_PIN 23 +#define Z_MIN_PIN 10 +#define Z_MAX_PIN 30 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 30 + #define Z_MIN_PROBE_PIN 30 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN 37 +#define X_DIR_PIN 48 +#define X_ENABLE_PIN 29 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 49 +#define Y_ENABLE_PIN 28 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 42 -#define E1_ENABLE_PIN 25 +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 42 +#define E1_ENABLE_PIN 25 // Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 -#define E1_MS1_PIN 63 -#define E1_MS2_PIN 64 +#define X_MS1_PIN 40 +#define X_MS2_PIN 41 +#define Y_MS1_PIN 69 +#define Y_MS2_PIN 39 +#define Z_MS1_PIN 68 +#define Z_MS2_PIN 67 +#define E0_MS1_PIN 65 +#define E0_MS2_PIN 66 +#define E1_MS1_PIN 63 +#define E1_MS2_PIN 64 -#define DIGIPOTSS_PIN 38 +#define DIGIPOTSS_PIN 38 #define DIGIPOT_CHANNELS { 4,5,3,0,1 } // X Y Z E0 E1 digipot channels to stepper driver mapping #ifndef DIGIPOT_MOTOR_CURRENT #define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) @@ -116,122 +116,122 @@ // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 6 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 7 +#define HEATER_2_PIN 6 +#define HEATER_BED_PIN 3 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN 8 #endif -#define FAN1_PIN 6 -#define FAN2_PIN 2 +#define FAN1_PIN 6 +#define FAN2_PIN 2 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 4 -#define CASE_LIGHT_PIN 46 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 4 +#define CASE_LIGHT_PIN 46 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 3 // Analog Input + #define FILWIDTH_PIN 3 // Analog Input #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 31 // Pullup! -#define SPINDLE_DIR_PIN 32 +#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 31 // Pullup! +#define SPINDLE_DIR_PIN 32 // // M7/M8/M9 - Coolant Control // -#define COOLANT_MIST_PIN 22 -#define COOLANT_FLOOD_PIN 44 +#define COOLANT_MIST_PIN 22 +#define COOLANT_FLOOD_PIN 44 // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#define E_MUX2_PIN 84 // 84 in MK2 Firmware +#define E_MUX0_PIN 17 +#define E_MUX1_PIN 16 +#define E_MUX2_PIN 84 // 84 in MK2 Firmware // // LCD / Controller // #if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL - #define KILL_PIN 80 + #define KILL_PIN 80 #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL - #define LCD_PINS_RS 70 - #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 72 - #define LCD_PINS_D5 73 - #define LCD_PINS_D6 74 - #define LCD_PINS_D7 75 + #define LCD_PINS_RS 70 + #define LCD_PINS_ENABLE 71 + #define LCD_PINS_D4 72 + #define LCD_PINS_D5 73 + #define LCD_PINS_D6 74 + #define LCD_PINS_D7 75 #if ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 44 + #define BEEPER_PIN 44 // NB: Panucatt's Viki 2.0 wiring diagram (v1.2) indicates that the // beeper/buzzer is connected to pin 33; however, the pin used in the // diagram is actually pin 44, so this is correct. - #define DOGLCD_A0 70 - #define DOGLCD_CS 71 + #define DOGLCD_A0 70 + #define DOGLCD_CS 71 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 85 - #define BTN_EN2 84 - #define BTN_ENC 83 + #define BTN_EN1 85 + #define BTN_EN2 84 + #define BTN_ENC 83 - #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board + #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board - #define STAT_LED_RED_PIN 22 - #define STAT_LED_BLUE_PIN 32 + #define STAT_LED_RED_PIN 22 + #define STAT_LED_BLUE_PIN 32 - #else // !VIKI2 && !miniVIKI + #else // !VIKI2 && !miniVIKI - #define BEEPER_PIN 79 // AUX-4 + #define BEEPER_PIN 79 // AUX-4 // AUX-2 - #define BTN_EN1 76 - #define BTN_EN2 77 - #define BTN_ENC 78 + #define BTN_EN1 76 + #define BTN_EN2 77 + #define BTN_ENC 78 - #define SD_DETECT_PIN 81 + #define SD_DETECT_PIN 81 #endif // !VIKI2 && !miniVIKI - #else // !NEWPANEL - old style panel with shift register + #else // !NEWPANEL - old style panel with shift register // No Beeper added - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK 38 + //#define SHIFT_LD 42 + //#define SHIFT_OUT 40 + //#define SHIFT_EN 17 - #define LCD_PINS_RS 75 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS 75 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #endif // !NEWPANEL diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index 2bb6e9b979..49237c7062 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -34,126 +34,126 @@ // // Servos // -#define SERVO0_PIN 22 // Motor header MX1 -#define SERVO1_PIN 23 // Motor header MX2 -#define SERVO2_PIN 24 // Motor header MX3 -#define SERVO3_PIN 5 // PWM header pin 5 +#define SERVO0_PIN 22 // Motor header MX1 +#define SERVO1_PIN 23 // Motor header MX2 +#define SERVO2_PIN 24 // Motor header MX3 +#define SERVO3_PIN 5 // PWM header pin 5 // // Limit Switches // -#define X_MIN_PIN 12 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 23 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 30 +#define X_MIN_PIN 12 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 11 +#define Y_MAX_PIN 23 +#define Z_MIN_PIN 10 +#define Z_MAX_PIN 30 // // Z Probe (when not Z_MIN_IN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 30 + #define Z_MIN_PROBE_PIN 30 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN 37 +#define X_DIR_PIN 48 +#define X_ENABLE_PIN 29 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 49 +#define Y_ENABLE_PIN 28 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 42 -#define E1_ENABLE_PIN 25 +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 42 +#define E1_ENABLE_PIN 25 // Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 -#define E1_MS1_PIN 63 -#define E1_MS2_PIN 64 +#define X_MS1_PIN 40 +#define X_MS2_PIN 41 +#define Y_MS1_PIN 69 +#define Y_MS2_PIN 39 +#define Z_MS1_PIN 68 +#define Z_MS2_PIN 67 +#define E0_MS1_PIN 65 +#define E0_MS2_PIN 66 +#define E1_MS1_PIN 63 +#define E1_MS2_PIN 64 -#define DIGIPOTSS_PIN 38 +#define DIGIPOTSS_PIN 38 #define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_BED_PIN 7 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_BED_PIN 7 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 7 +#define HEATER_BED_PIN 3 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN 8 #endif -#define FAN1_PIN 6 -#define FAN2_PIN 2 +#define FAN1_PIN 6 +#define FAN2_PIN 2 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 4 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 4 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 3 // Analog Input + #define FILWIDTH_PIN 3 // Analog Input #endif // // LCD / Controller // -#define LCD_PINS_RS 70 // Ext2_5 -#define LCD_PINS_ENABLE 71 // Ext2_7 -#define LCD_PINS_D4 72 // Ext2_9 ? -#define LCD_PINS_D5 73 // Ext2_11 ? -#define LCD_PINS_D6 74 // Ext2_13 -#define LCD_PINS_D7 75 // Ext2_15 ? -#define BEEPER_PIN -1 +#define LCD_PINS_RS 70 // Ext2_5 +#define LCD_PINS_ENABLE 71 // Ext2_7 +#define LCD_PINS_D4 72 // Ext2_9 ? +#define LCD_PINS_D5 73 // Ext2_11 ? +#define LCD_PINS_D6 74 // Ext2_13 +#define LCD_PINS_D7 75 // Ext2_15 ? +#define BEEPER_PIN -1 -#define BTN_HOME 80 // Ext_16 -#define BTN_CENTER 81 // Ext_14 -#define BTN_ENC BTN_CENTER -#define BTN_RIGHT 82 // Ext_12 -#define BTN_LEFT 83 // Ext_10 -#define BTN_UP 84 // Ext2_8 -#define BTN_DOWN 85 // Ext2_6 +#define BTN_HOME 80 // Ext_16 +#define BTN_CENTER 81 // Ext_14 +#define BTN_ENC BTN_CENTER +#define BTN_RIGHT 82 // Ext_12 +#define BTN_LEFT 83 // Ext_10 +#define BTN_UP 84 // Ext2_8 +#define BTN_DOWN 85 // Ext2_6 -#define HOME_PIN BTN_HOME +#define HOME_PIN BTN_HOME #if ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 44 + #define BEEPER_PIN 44 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 70 - #define DOGLCD_CS 71 + #define DOGLCD_A0 70 + #define DOGLCD_CS 71 #define LCD_SCREEN_ROT_180 - #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board + #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board - #define STAT_LED_RED_PIN 22 - #define STAT_LED_BLUE_PIN 32 + #define STAT_LED_RED_PIN 22 + #define STAT_LED_BLUE_PIN 32 #endif // VIKI2/miniVIKI diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 3f537a6663..69d2ac2088 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -40,11 +40,11 @@ // // Heaters / Fans // -#define RAMPS_D8_PIN 9 -#define RAMPS_D9_PIN 8 -#define MOSFET_D_PIN 12 +#define RAMPS_D8_PIN 9 +#define RAMPS_D9_PIN 8 +#define MOSFET_D_PIN 12 -#define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header +#define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header #include "pins_RAMPS.h" @@ -57,21 +57,21 @@ // Steppers // #undef Z_ENABLE_PIN -#define Z_ENABLE_PIN 63 +#define Z_ENABLE_PIN 63 // // Heaters / Fans // -#define HEATER_2_PIN 6 +#define HEATER_2_PIN 6 // // Misc. Functions // #undef SDSS -#define SDSS 25 +#define SDSS 25 #undef SD_DETECT_PIN -#define SD_DETECT_PIN 53 +#define SD_DETECT_PIN 53 // // LCD / Controller @@ -85,24 +85,24 @@ #undef LCD_PINS_D5 #undef LCD_PINS_D6 #undef LCD_PINS_D7 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 35 - #define LCD_PINS_D6 33 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 37 + #define LCD_PINS_D5 35 + #define LCD_PINS_D6 33 + #define LCD_PINS_D7 31 // Buttons #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 23 + #define BTN_EN1 16 + #define BTN_EN2 17 + #define BTN_ENC 23 #else - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #endif // HAS_SPI_LCD && NEWPANEL @@ -137,7 +137,7 @@ * * Note: Socket names vary from vendor to vendor */ -#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not good with 3DRAG +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not good with 3DRAG #undef SPINDLE_LASER_ENA_PIN #undef SPINDLE_DIR_PIN @@ -149,14 +149,14 @@ #undef Z_DIR_PIN #undef Z_ENABLE_PIN #undef Z_STEP_PIN - #define Z_DIR_PIN 28 - #define Z_ENABLE_PIN 24 - #define Z_STEP_PIN 26 - #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 62 // Pullup! - #define SPINDLE_DIR_PIN 48 - #elif !BOTH(ULTRA_LCD, NEWPANEL) // use expansion header if no LCD in use - #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! - #define SPINDLE_DIR_PIN 17 + #define Z_DIR_PIN 28 + #define Z_ENABLE_PIN 24 + #define Z_STEP_PIN 26 + #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 62 // Pullup! + #define SPINDLE_DIR_PIN 48 + #elif !BOTH(ULTRA_LCD, NEWPANEL) // use expansion header if no LCD in use + #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 17 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index 99b75d5e00..a38e4e1b43 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -32,15 +32,15 @@ #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) - #define CASE_LIGHT_PIN 6 // Define before RAMPS pins include + #define CASE_LIGHT_PIN 6 // Define before RAMPS pins include #endif #define BOARD_INFO_NAME "Azteeg X3" // // Servos // -#define SERVO0_PIN 44 // SERVO1 port -#define SERVO1_PIN 55 // SERVO2 port +#define SERVO0_PIN 44 // SERVO1 port +#define SERVO1_PIN 55 // SERVO2 port #include "pins_RAMPS_13.h" @@ -55,17 +55,17 @@ #undef DOGLCD_A0 #undef DOGLCD_CS #undef BTN_ENC - #define DOGLCD_A0 31 - #define DOGLCD_CS 32 - #define BTN_ENC 12 + #define DOGLCD_A0 31 + #define DOGLCD_CS 32 + #define BTN_ENC 12 - #define STAT_LED_RED_PIN 64 - #define STAT_LED_BLUE_PIN 63 + #define STAT_LED_RED_PIN 64 + #define STAT_LED_BLUE_PIN 63 #else - #define STAT_LED_RED_PIN 6 - #define STAT_LED_BLUE_PIN 11 + #define STAT_LED_RED_PIN 6 + #define STAT_LED_BLUE_PIN 11 #endif @@ -79,18 +79,18 @@ // // M3/M4/M5 - Spindle/Laser Control // -#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3 board +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3 board #undef SPINDLE_LASER_ENA_PIN #undef SPINDLE_DIR_PIN #if HAS_CUTTER - #undef SDA // use EXP3 header + #undef SDA // use EXP3 header #undef SCL #if SERVO0_PIN == 7 #undef SERVO0_PIN - #define SERVO0_PIN 11 + #define SERVO0_PIN 11 #endif - #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 20 // Pullup! - #define SPINDLE_DIR_PIN 21 + #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 20 // Pullup! + #define SPINDLE_DIR_PIN 21 #endif diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index 627eaabfd6..c8e2a6683d 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -43,21 +43,21 @@ // Tested this pin with bed leveling on a Delta with 1 servo. // Physical wire attachment on EXT1: GND, 5V, D47. // -#define SERVO0_PIN 47 +#define SERVO0_PIN 47 // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 -#define Z_STOP_PIN 18 +#define X_STOP_PIN 3 +#define Y_STOP_PIN 14 +#define Z_STOP_PIN 18 #ifndef FAN_PIN - #define FAN_PIN 6 + #define FAN_PIN 6 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) - #define CASE_LIGHT_PIN 44 + #define CASE_LIGHT_PIN 44 #endif // @@ -67,100 +67,100 @@ // DIGIPOT slave addresses #ifndef DIGIPOT_I2C_ADDRESS_A - #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT 0x2C (0x58 <- 0x2C << 1) + #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT 0x2C (0x58 <- 0x2C << 1) #endif #ifndef DIGIPOT_I2C_ADDRESS_B - #define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT 0x2E (0x5C <- 0x2E << 1) + #define DIGIPOT_I2C_ADDRESS_B 0x2E // unshifted slave address for second DIGIPOT 0x2E (0x5C <- 0x2E << 1) #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 18 + #define Z_MIN_PROBE_PIN 18 #endif // // Steppers // -#define E2_STEP_PIN 23 -#define E2_DIR_PIN 25 -#define E2_ENABLE_PIN 40 +#define E2_STEP_PIN 23 +#define E2_DIR_PIN 25 +#define E2_ENABLE_PIN 40 -#define E3_STEP_PIN 27 -#define E3_DIR_PIN 29 -#define E3_ENABLE_PIN 41 +#define E3_STEP_PIN 27 +#define E3_DIR_PIN 29 +#define E3_ENABLE_PIN 41 -#define E4_STEP_PIN 43 -#define E4_DIR_PIN 37 -#define E4_ENABLE_PIN 42 +#define E4_STEP_PIN 43 +#define E4_DIR_PIN 37 +#define E4_ENABLE_PIN 42 // // Temperature Sensors // -#define TEMP_2_PIN 12 // Analog Input -#define TEMP_3_PIN 11 // Analog Input -#define TEMP_4_PIN 10 // Analog Input -#define TC1 4 // Analog Input (Thermo couple on Azteeg X3Pro) -#define TC2 5 // Analog Input (Thermo couple on Azteeg X3Pro) +#define TEMP_2_PIN 12 // Analog Input +#define TEMP_3_PIN 11 // Analog Input +#define TEMP_4_PIN 10 // Analog Input +#define TC1 4 // Analog Input (Thermo couple on Azteeg X3Pro) +#define TC2 5 // Analog Input (Thermo couple on Azteeg X3Pro) // // Heaters / Fans // -#define HEATER_2_PIN 16 -#define HEATER_3_PIN 17 -#define HEATER_4_PIN 4 -#define HEATER_5_PIN 5 -#define HEATER_6_PIN 6 -#define HEATER_7_PIN 11 +#define HEATER_2_PIN 16 +#define HEATER_3_PIN 17 +#define HEATER_4_PIN 4 +#define HEATER_5_PIN 5 +#define HEATER_6_PIN 6 +#define HEATER_7_PIN 11 #ifndef CONTROLLER_FAN_PIN - #define CONTROLLER_FAN_PIN 4 // Pin used for the fan to cool motherboard (-1 to disable) + #define CONTROLLER_FAN_PIN 4 // Pin used for the fan to cool motherboard (-1 to disable) #endif // Fans/Water Pump to cool the hotend cool side. -#define ORIG_E0_AUTO_FAN_PIN 5 -#define ORIG_E1_AUTO_FAN_PIN 5 -#define ORIG_E2_AUTO_FAN_PIN 5 -#define ORIG_E3_AUTO_FAN_PIN 5 +#define ORIG_E0_AUTO_FAN_PIN 5 +#define ORIG_E1_AUTO_FAN_PIN 5 +#define ORIG_E2_AUTO_FAN_PIN 5 +#define ORIG_E3_AUTO_FAN_PIN 5 // // LCD / Controller // #undef BEEPER_PIN -#define BEEPER_PIN 33 +#define BEEPER_PIN 33 #if ANY(VIKI2, miniVIKI) #undef SD_DETECT_PIN - #define SD_DETECT_PIN 49 // For easy adapter board + #define SD_DETECT_PIN 49 // For easy adapter board #undef BEEPER_PIN - #define BEEPER_PIN 12 // 33 isn't physically available to the LCD display + #define BEEPER_PIN 12 // 33 isn't physically available to the LCD display #else - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define STAT_LED_RED_PIN 32 + #define STAT_LED_BLUE_PIN 35 #endif // // Misc. Functions // #if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN - #undef DOGLCD_A0 // Steal pin 44 for the case light; if you have a Viki2 and have connected it - #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments + #undef DOGLCD_A0 // Steal pin 44 for the case light; if you have a Viki2 and have connected it + #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments // as the wiring diagram uses pin 44 for DOGLCD_A0 #endif // // M3/M4/M5 - Spindle/Laser Control // -#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3pro board +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3pro board #undef SPINDLE_LASER_ENA_PIN #undef SPINDLE_DIR_PIN -#if HAS_CUTTER // EXP2 header +#if HAS_CUTTER // EXP2 header #if ANY(VIKI2, miniVIKI) - #define BTN_EN2 31 // Pin 7 needed for Spindle PWM + #define BTN_EN2 31 // Pin 7 needed for Spindle PWM #endif - #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 20 // Pullup! - #define SPINDLE_DIR_PIN 21 + #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 20 // Pullup! + #define SPINDLE_DIR_PIN 21 #endif diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index 9945c94d76..1aa9b67f7c 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -34,9 +34,9 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 66 // Pullup or pulldown! -#define SPINDLE_DIR_PIN 67 -#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 66 // Pullup or pulldown! +#define SPINDLE_DIR_PIN 67 +#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM #include "pins_RAMPS.h" @@ -45,5 +45,5 @@ // #undef TEMP_0_PIN #undef TEMP_1_PIN -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN 11 // Analog Input +#define TEMP_0_PIN 9 // Analog Input +#define TEMP_1_PIN 11 // Analog Input diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index bf75c1a2a2..44b6ff1e61 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -34,30 +34,30 @@ // // Heaters / Fans // -#define RAMPS_D8_PIN 10 -#define RAMPS_D9_PIN 12 -#define RAMPS_D10_PIN 9 -#define MOSFET_D_PIN 7 +#define RAMPS_D8_PIN 10 +#define RAMPS_D9_PIN 12 +#define RAMPS_D10_PIN 9 +#define MOSFET_D_PIN 7 // // Auto fans // -#define ORIG_E0_AUTO_FAN_PIN 11 -#define ORIG_E1_AUTO_FAN_PIN 6 -#define ORIG_E2_AUTO_FAN_PIN 6 -#define ORIG_E3_AUTO_FAN_PIN 6 +#define ORIG_E0_AUTO_FAN_PIN 11 +#define ORIG_E1_AUTO_FAN_PIN 6 +#define ORIG_E2_AUTO_FAN_PIN 6 +#define ORIG_E3_AUTO_FAN_PIN 6 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM -#define SPINDLE_DIR_PIN 42 +#define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM +#define SPINDLE_DIR_PIN 42 // // Limit Switches // -#define X_MAX_PIN 79 // 2 +#define X_MAX_PIN 79 // 2 // // Import RAMPS 1.3 pins @@ -68,34 +68,33 @@ // Z Probe (when not Z_MIN_PIN) // #undef Z_MIN_PROBE_PIN -#define Z_MIN_PROBE_PIN 19 // IND_S_5V +#define Z_MIN_PROBE_PIN 19 // IND_S_5V #undef Z_ENABLE_PIN -#define Z_ENABLE_PIN 77 // 62 +#define Z_ENABLE_PIN 77 // 62 // // Steppers // -#define DIGIPOTSS_PIN 22 +#define DIGIPOTSS_PIN 22 #define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // // Temperature Sensors // #undef TEMP_1_PIN -#define TEMP_1_PIN 14 // Analog Input (15) +#define TEMP_1_PIN 14 // Analog Input (15) #undef TEMP_BED_PIN -#define TEMP_BED_PIN 15 // Analog Input (14) +#define TEMP_BED_PIN 15 // Analog Input (14) // // Misc. Functions // -#undef PS_ON_PIN // 12 -#define PS_ON_PIN 81 // External Power Supply - -#define CASE_LIGHT_PIN 44 // Hardware PWM +#undef PS_ON_PIN // 12 +#define PS_ON_PIN 81 // External Power Supply +#define CASE_LIGHT_PIN 44 // Hardware PWM // This board has headers for Z-min, Z-max and IND_S_5V *but* as the bq team // decided to ship the printer only with the probe and no additional Z-min @@ -104,8 +103,8 @@ #ifdef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN #undef Z_MIN_PIN #undef Z_MAX_PIN - #define Z_MIN_PIN 19 // IND_S_5V - #define Z_MAX_PIN 18 // Z-MIN Label + #define Z_MIN_PIN 19 // IND_S_5V + #define Z_MAX_PIN 18 // Z-MIN Label #endif // @@ -113,5 +112,5 @@ // #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef HEATER_BED_PIN - #define HEATER_BED_PIN 8 + #define HEATER_BED_PIN 8 #endif diff --git a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h index 6a98973347..9ff9d3be62 100644 --- a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h +++ b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h @@ -34,68 +34,68 @@ // // Limit Switches // -#define X_STOP_PIN 54 // PF0 / A0 -#define Y_STOP_PIN 24 // PA2 / AD2 -#define Z_MIN_PIN 23 // PA1 / AD1 -#define Z_MAX_PIN 25 // PA3 / AD3 -#define SERVO0_PIN 40 // PG1 / !RD +#define X_STOP_PIN 54 // PF0 / A0 +#define Y_STOP_PIN 24 // PA2 / AD2 +#define Z_MIN_PIN 23 // PA1 / AD1 +#define Z_MAX_PIN 25 // PA3 / AD3 +#define SERVO0_PIN 40 // PG1 / !RD // // Steppers // -#define X_STEP_PIN 61 // PF7 / A7 -#define X_DIR_PIN 62 // PK0 / A8 -#define X_ENABLE_PIN 60 // PF6 / A6 +#define X_STEP_PIN 61 // PF7 / A7 +#define X_DIR_PIN 62 // PK0 / A8 +#define X_ENABLE_PIN 60 // PF6 / A6 -#define Y_STEP_PIN 64 // PK2 / A10 -#define Y_DIR_PIN 65 // PK3 / A11 -#define Y_ENABLE_PIN 63 // PK1 / A9 +#define Y_STEP_PIN 64 // PK2 / A10 +#define Y_DIR_PIN 65 // PK3 / A11 +#define Y_ENABLE_PIN 63 // PK1 / A9 -#define Z_STEP_PIN 67 // PK5 / A13 -#define Z_DIR_PIN 69 // PK7 / A15 -#define Z_ENABLE_PIN 66 // PK4 / A12 -#define Z_MIN_PROBE_PIN 25 // PA3 / AD3 +#define Z_STEP_PIN 67 // PK5 / A13 +#define Z_DIR_PIN 69 // PK7 / A15 +#define Z_ENABLE_PIN 66 // PK4 / A12 +#define Z_MIN_PROBE_PIN 25 // PA3 / AD3 -#define E0_STEP_PIN 58 // PF4 / A4 -#define E0_DIR_PIN 59 // PF5 / A5 -#define E0_ENABLE_PIN 57 // PF3 / A3 +#define E0_STEP_PIN 58 // PF4 / A4 +#define E0_DIR_PIN 59 // PF5 / A5 +#define E0_ENABLE_PIN 57 // PF3 / A3 // // Temperature Sensors // -#define TEMP_0_PIN 1 // PF1 / A1 Analog -#define TEMP_BED_PIN 14 // PK6 / A14 Analog +#define TEMP_0_PIN 1 // PF1 / A1 Analog +#define TEMP_BED_PIN 14 // PK6 / A14 Analog // // Heaters / Fans // -#define HEATER_0_PIN 4 // PG5 / PWM4 -#define HEATER_BED_PIN 3 // PE5 / PWM3 +#define HEATER_0_PIN 4 // PG5 / PWM4 +#define HEATER_BED_PIN 3 // PE5 / PWM3 -#define FAN_PIN 5 // PE3 / PWM5 +#define FAN_PIN 5 // PE3 / PWM5 // // Misc. Functions // -#define SDSS 53 // PB0 / SS -#define LED_PIN 13 // PB7 / PWM13 +#define SDSS 53 // PB0 / SS +#define LED_PIN 13 // PB7 / PWM13 -#define MISO_PIN 50 // PB3 -#define MOSI_PIN 51 // PB2 -#define SCK_PIN 52 // PB1 +#define MISO_PIN 50 // PB3 +#define MOSI_PIN 51 // PB2 +#define SCK_PIN 52 // PB1 // // LCDs and Controllers // #if HAS_SPI_LCD #if ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS 2 - #define LCD_PINS_ENABLE 36 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 34 - #define LCD_PINS_D6 35 - #define LCD_PINS_D7 32 - #define ADC_KEYPAD_PIN 12 // Analog + #define LCD_PINS_RS 2 + #define LCD_PINS_ENABLE 36 + #define LCD_PINS_D4 37 + #define LCD_PINS_D5 34 + #define LCD_PINS_D6 35 + #define LCD_PINS_D7 32 + #define ADC_KEYPAD_PIN 12 // Analog #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FELIX2.h b/Marlin/src/pins/ramps/pins_FELIX2.h index f5a49db533..bfd341db6d 100644 --- a/Marlin/src/pins/ramps/pins_FELIX2.h +++ b/Marlin/src/pins/ramps/pins_FELIX2.h @@ -35,29 +35,29 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 #include "pins_RAMPS.h" // // Misc. Functions // -#define SDPOWER_PIN 1 +#define SDPOWER_PIN 1 -#define PS_ON_PIN 12 +#define PS_ON_PIN 12 // // LCD / Controller // #if BOTH(ULTRA_LCD, NEWPANEL) - #define SD_DETECT_PIN 6 + #define SD_DETECT_PIN 6 #endif // NEWPANEL && ULTRA_LCD // // M3/M4/M5 - Spindle/Laser Control // -#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not valid with this board +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not valid with this board #undef SPINDLE_LASER_ENA_PIN #undef SPINDLE_DIR_PIN diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 3dcd7e57bc..75d647fed5 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -41,83 +41,83 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN 6 -#define SERVO2_PIN 5 +#define SERVO0_PIN 11 +#define SERVO1_PIN 6 +#define SERVO2_PIN 5 // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN 3 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN 2 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN 53 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN 49 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN 40 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN 42 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN 44 #endif -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 43 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN 42 +#define E2_DIR_PIN 43 +#define E2_ENABLE_PIN 44 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN 13 // Analog Input +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_BED_PIN 14 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -140,39 +140,39 @@ // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 7 +#define HEATER_BED_PIN 8 #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN 9 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 57 + #define FIL_RUNOUT_PIN 57 #endif #if !HAS_FILAMENT_SENSOR - #define FAN1_PIN 4 + #define FAN1_PIN 4 #endif // // Misc. Functions // #ifndef SDSS - #define SDSS 53 + #define SDSS 53 #endif -#define LED_PIN 13 -#define LED4_PIN 5 +#define LED_PIN 13 +#define LED4_PIN 5 // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // Analog Input +#define FILWIDTH_PIN 5 // Analog Input #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif -#define CASE_LIGHT_PIN 5 +#define CASE_LIGHT_PIN 5 // // LCD / Controller @@ -180,16 +180,16 @@ // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define BEEPER_PIN 37 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h index 3bbff7f8f2..3ed9fb9692 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h @@ -28,10 +28,10 @@ #define BOARD_INFO_NAME "Formbot Raptor2" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#define FAN_PIN 6 +#define FAN_PIN 6 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 22 + #define FIL_RUNOUT_PIN 22 #endif #include "pins_FORMBOT_RAPTOR.h" @@ -42,22 +42,22 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) - #if !NUM_SERVOS // Try to use servo connector first - #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_DIR_PIN 5 - #elif !GREEDY_PANEL // Try to use AUX2 - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #if !NUM_SERVOS // Try to use servo connector first + #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM + #define SPINDLE_DIR_PIN 5 + #elif !GREEDY_PANEL // Try to use AUX2 + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_DIR_PIN 65 #endif #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) - #if NUM_SERVOS <= 1 // Try to use servo connector first - #define CASE_LIGHT_PIN 6 // Hardware PWM - #elif !GREEDY_PANEL // Try to use AUX2 - #define CASE_LIGHT_PIN 44 // Hardware PWM + #if NUM_SERVOS <= 1 // Try to use servo connector first + #define CASE_LIGHT_PIN 6 // Hardware PWM + #elif !GREEDY_PANEL // Try to use AUX2 + #define CASE_LIGHT_PIN 44 // Hardware PWM #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 1c911cd125..8fa3686514 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -37,84 +37,84 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN -1 // was 6 -#define SERVO2_PIN -1 // was 5 -#define SERVO3_PIN -1 +#define SERVO0_PIN 11 +#define SERVO1_PIN -1 // was 6 +#define SERVO2_PIN -1 // was 5 +#define SERVO3_PIN -1 // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN 3 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN 2 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN 53 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN 49 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN 40 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN 42 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN 44 #endif -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 43 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN 42 +#define E2_DIR_PIN 43 +#define E2_ENABLE_PIN 44 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 3 // Analog Input +#define TEMP_0_PIN 13 // Analog Input +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_BED_PIN 3 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -137,36 +137,36 @@ // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 58 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 7 +#define HEATER_BED_PIN 58 -#define FAN_PIN 9 +#define FAN_PIN 9 #if HAS_FILAMENT_SENSOR - #define FIL_RUNOUT_PIN 4 - //#define FIL_RUNOUT2_PIN -1 + #define FIL_RUNOUT_PIN 4 + //#define FIL_RUNOUT2_PIN -1 #else // Though defined as a fan pin, it is utilized as a dedicated laser pin by Formbot. - #define FAN1_PIN 4 + #define FAN1_PIN 4 #endif // // Misc. Functions // -#define SDSS 53 +#define SDSS 53 #ifndef LED_PIN - #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED + #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED #endif // is a good place to get a signal to control the Max7219 LED Matrix. // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // Analog Input +#define FILWIDTH_PIN 5 // Analog Input #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif -#define CASE_LIGHT_PIN 8 +#define CASE_LIGHT_PIN 8 // // LCD / Controller @@ -175,22 +175,22 @@ // #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) #ifndef BEEPER_PIN - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #endif - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 // Allow MAX7219 to steal the KILL pin #if !defined(KILL_PIN) && MAX7219_CLK_PIN != 41 && MAX7219_DIN_PIN != 41 && MAX7219_LOAD_PIN != 41 - #define KILL_PIN 41 + #define KILL_PIN 41 #endif - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index bdcb28dac2..3846a7649e 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -37,116 +37,114 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN -1 // was 6 -#define SERVO2_PIN -1 -#define SERVO3_PIN -1 +#define SERVO0_PIN 11 +#define SERVO1_PIN -1 // was 6 +#define SERVO2_PIN -1 +#define SERVO3_PIN -1 // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN 3 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN 2 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN 53 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN 49 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN 40 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN 42 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN 44 #endif -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 43 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN 42 +#define E2_DIR_PIN 43 +#define E2_ENABLE_PIN 44 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN 13 // Analog Input +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_BED_PIN 14 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif - - // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 7 +#define HEATER_BED_PIN 8 -#define FAN_PIN 9 -#define FAN1_PIN 12 +#define FAN_PIN 9 +#define FAN1_PIN 12 -#define NUM_RUNOUT_SENSORS 2 -#define FIL_RUNOUT_PIN 22 -#define FIL_RUNOUT2_PIN 21 +#define NUM_RUNOUT_SENSORS 2 +#define FIL_RUNOUT_PIN 22 +#define FIL_RUNOUT2_PIN 21 // // Misc. Functions // -#define CASE_LIGHT_PIN 5 -#define SDSS 53 +#define CASE_LIGHT_PIN 5 +#define SDSS 53 #ifndef LED_PIN - #define LED_PIN 13 + #define LED_PIN 13 #endif -#define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 4 // Pullup! +#define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 4 // Pullup! // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // Analog Input +#define FILWIDTH_PIN 5 // Analog Input // // LCD / Controller @@ -154,20 +152,20 @@ // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 #ifndef KILL_PIN - #define KILL_PIN 41 + #define KILL_PIN 41 #endif #ifndef BEEPER_PIN - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 6b7f2d582b..19238bc5f8 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -33,83 +33,83 @@ #define BOARD_INFO_NAME "FYSETC F6 1.3" #endif -#define RESET_PIN 30 -#define SPI_FLASH_CS 83 +#define RESET_PIN 30 +#define SPI_FLASH_CS 83 // // Servos // -#define SERVO0_PIN 13 -#define SERVO1_PIN 11 // (PS_ON_PIN) -#define SERVO2_PIN 10 // (FIL_RUNOUT_PIN) -#define SERVO3_PIN 4 // (RGB_LED_G_PIN) +#define SERVO0_PIN 13 +#define SERVO1_PIN 11 // (PS_ON_PIN) +#define SERVO2_PIN 10 // (FIL_RUNOUT_PIN) +#define SERVO3_PIN 4 // (RGB_LED_G_PIN) // // Limit Switches // -#define X_MIN_PIN 63 -#define X_MAX_PIN 64 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 12 +#define X_MIN_PIN 63 +#define X_MAX_PIN 64 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 12 #ifndef Z_MAX_PIN - #define Z_MAX_PIN 9 + #define Z_MAX_PIN 9 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN SERVO2_PIN + #define FIL_RUNOUT_PIN SERVO2_PIN #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 9 // Servos pin + #define Z_MIN_PROBE_PIN 9 // Servos pin #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 70 + #define X_CS_PIN 70 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 39 + #define Y_CS_PIN 39 #endif -#define Z_STEP_PIN 43 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 58 +#define Z_STEP_PIN 43 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 58 #ifndef Z_CS_PIN - #define Z_CS_PIN 74 + #define Z_CS_PIN 74 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 47 + #define E0_CS_PIN 47 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN 32 + #define E1_CS_PIN 32 #endif -#define E2_STEP_PIN 59 -#define E2_DIR_PIN 57 -#define E2_ENABLE_PIN 40 +#define E2_STEP_PIN 59 +#define E2_DIR_PIN 57 +#define E2_ENABLE_PIN 40 #ifndef E2_CS_PIN - #define E2_CS_PIN 42 + #define E2_CS_PIN 42 #endif // @@ -125,76 +125,76 @@ * At the moment, F6 rx pins are not pc interrupt pins */ #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN -1 // 71 + #define X_SERIAL_RX_PIN -1 // 71 #endif #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 72 + #define X_SERIAL_TX_PIN 72 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN -1 // 73 + #define Y_SERIAL_RX_PIN -1 // 73 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 75 + #define Y_SERIAL_TX_PIN 75 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN -1 // 78 + #define Z_SERIAL_RX_PIN -1 // 78 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 79 + #define Z_SERIAL_TX_PIN 79 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN -1 // 76 + #define E0_SERIAL_RX_PIN -1 // 76 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 77 + #define E0_SERIAL_TX_PIN 77 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 // 80 + #define E1_SERIAL_RX_PIN -1 // 80 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN 81 + #define E1_SERIAL_TX_PIN 81 #endif #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 // 22 + #define E2_SERIAL_RX_PIN -1 // 22 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN 82 + #define E2_SERIAL_TX_PIN 82 #endif #endif // // Temperature Sensors // -#define TEMP_0_PIN 12 // Analog Input -#define TEMP_1_PIN 13 // Analog Input -#define TEMP_2_PIN 14 // Analog Input -#define TEMP_BED_PIN 15 // Analog Input +#define TEMP_0_PIN 12 // Analog Input +#define TEMP_1_PIN 13 // Analog Input +#define TEMP_2_PIN 14 // Analog Input +#define TEMP_BED_PIN 15 // Analog Input #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 9 // Analog Input on X+ endstop + #define FILWIDTH_PIN 9 // Analog Input on X+ endstop #endif // // Heaters / Fans // -#define HEATER_0_PIN 5 -#define HEATER_1_PIN 6 -#define HEATER_2_PIN 7 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN 5 +#define HEATER_1_PIN 6 +#define HEATER_2_PIN 7 +#define HEATER_BED_PIN 8 -#define FAN_PIN 44 -#define FAN1_PIN 45 -#define FAN2_PIN 46 +#define FAN_PIN 44 +#define FAN1_PIN 45 +#define FAN2_PIN 46 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define KILL_PIN 41 +#define SDSS 53 +#define LED_PIN 13 +#define KILL_PIN 41 #ifndef PS_ON_PIN - #define PS_ON_PIN SERVO1_PIN + #define PS_ON_PIN SERVO1_PIN #endif /** @@ -211,69 +211,69 @@ // // LCDs and Controllers // -#define BEEPER_PIN 37 -#define SD_DETECT_PIN 49 +#define BEEPER_PIN 37 +#define SD_DETECT_PIN 49 #if ENABLED(FYSETC_MINI_12864) // // See https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 // - #define DOGLCD_A0 16 - #define DOGLCD_CS 17 + #define DOGLCD_A0 16 + #define DOGLCD_CS 17 #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN 27 + #define LCD_BACKLIGHT_PIN 27 #endif - #define KILL_PIN 41 - #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. + #define KILL_PIN 41 + #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. // Seems to work best if left open. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN 25 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN 27 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN 29 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN 25 #endif #elif HAS_GRAPHICAL_LCD - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS 25 - #define DOGLCD_A0 27 + #define DOGLCD_CS 25 + #define DOGLCD_A0 27 #endif #endif #if ENABLED(NEWPANEL) - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 3 + #define RGB_LED_R_PIN 3 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 4 + #define RGB_LED_G_PIN 4 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 9 + #define RGB_LED_B_PIN 9 #endif #ifndef RGB_LED_W_PIN - #define RGB_LED_W_PIN -1 + #define RGB_LED_W_PIN -1 #endif diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h index dff4749fb7..f0eb0bf4c6 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h @@ -27,24 +27,24 @@ #define BOARD_NAME "FYSETC F6 1.4" -#define Z_MAX_PIN 2 +#define Z_MAX_PIN 2 #if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers */ - #define X_SERIAL_RX_PIN 72 - #define X_SERIAL_TX_PIN 71 - #define Y_SERIAL_RX_PIN 73 - #define Y_SERIAL_TX_PIN 78 - #define Z_SERIAL_RX_PIN 75 - #define Z_SERIAL_TX_PIN 79 - #define E0_SERIAL_RX_PIN 77 - #define E0_SERIAL_TX_PIN 81 - #define E1_SERIAL_RX_PIN 76 - #define E1_SERIAL_TX_PIN 80 - #define E2_SERIAL_RX_PIN 62 - #define E2_SERIAL_TX_PIN 82 + #define X_SERIAL_RX_PIN 72 + #define X_SERIAL_TX_PIN 71 + #define Y_SERIAL_RX_PIN 73 + #define Y_SERIAL_TX_PIN 78 + #define Z_SERIAL_RX_PIN 75 + #define Z_SERIAL_TX_PIN 79 + #define E0_SERIAL_RX_PIN 77 + #define E0_SERIAL_TX_PIN 81 + #define E1_SERIAL_RX_PIN 76 + #define E1_SERIAL_TX_PIN 80 + #define E2_SERIAL_RX_PIN 62 + #define E2_SERIAL_TX_PIN 82 #endif #include "pins_FYSETC_F6_13.h" diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index f0928b0ed1..4c5ba7eca1 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -40,8 +40,8 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 +#define X_STOP_PIN 3 +#define Y_STOP_PIN 14 #undef X_MIN_PIN #undef X_MAX_PIN @@ -52,13 +52,13 @@ // Steppers // #undef E1_STEP_PIN -#define E1_STEP_PIN 32 +#define E1_STEP_PIN 32 // // Heaters / Fans // #undef HEATER_1_PIN -#define HEATER_1_PIN 11 +#define HEATER_1_PIN 11 // // Misc. Functions @@ -69,5 +69,5 @@ #if Z_STEP_PIN == 26 #undef Z_STEP_PIN - #define Z_STEP_PIN 32 + #define Z_STEP_PIN 32 #endif diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index 8c426af17c..09f35b1fe0 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -37,73 +37,73 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 -#define Z_MIN_PIN 68 // Used for bed leveling -#define Z_MAX_PIN 66 +#define X_STOP_PIN 3 +#define Y_STOP_PIN 14 +#define Z_MIN_PIN 68 // Used for bed leveling +#define Z_MAX_PIN 66 // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 63 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 63 -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 -#define E1_STEP_PIN 32 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 32 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 // // Temperature Sensors // -#define TEMP_0_PIN 13 +#define TEMP_0_PIN 13 // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define FAN_PIN 8 -#define CONTROLLER_FAN_PIN 9 +#define HEATER_0_PIN 10 +#define FAN_PIN 8 +#define CONTROLLER_FAN_PIN 9 // // Misc. Functions // -#define SDSS 25 +#define SDSS 25 -#define FIL_RUNOUT_PIN 69 // PK7 -#define KILL_PIN 20 // PD1 +#define FIL_RUNOUT_PIN 69 // PK7 +#define KILL_PIN 20 // PD1 // // LCD / Controller // -#define SD_DETECT_PIN 21 // PD0 -#define LCD_SDSS 53 -#define BEEPER_PIN 6 +#define SD_DETECT_PIN 21 // PD0 +#define LCD_SDSS 53 +#define BEEPER_PIN 6 -#define DOGLCD_CS 29 -#define DOGLCD_A0 27 +#define DOGLCD_CS 29 +#define DOGLCD_A0 27 -#define LCD_PINS_RS 27 -#define LCD_PINS_ENABLE 29 -#define LCD_PINS_D4 37 -#define LCD_PINS_D5 35 -#define LCD_PINS_D6 33 -#define LCD_PINS_D7 31 +#define LCD_PINS_RS 27 +#define LCD_PINS_ENABLE 29 +#define LCD_PINS_D4 37 +#define LCD_PINS_D5 35 +#define LCD_PINS_D6 33 +#define LCD_PINS_D7 31 #if ENABLED(NEWPANEL) - #define BTN_EN1 17 - #define BTN_EN2 16 - #define BTN_ENC 23 + #define BTN_EN1 17 + #define BTN_EN2 16 + #define BTN_ENC 23 #endif diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h index b1564ea2c3..057b51a584 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h @@ -30,28 +30,28 @@ #endif #define BOARD_INFO_NAME "MKS BASE 1.4" -#define MKS_BASE_VERSION 14 +#define MKS_BASE_VERSION 14 // // Heaters / Fans // -#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 +#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 // Other Mods -#define CASE_LIGHT_PIN 11 // PB5 ** Pin24 ** PWM11 -#define SERVO3_PIN 12 // PB6 ** Pin25 ** D12 -#define PS_ON_PIN 2 // X+ // PE4 ** Pin6 ** PWM2 **MUST BE HARDWARE PWM -#define FILWIDTH_PIN 15 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup! -#define FIL_RUNOUT_PIN 19 // Z+ // PD2 ** Pin45 ** USART1_RX +#define CASE_LIGHT_PIN 11 // PB5 ** Pin24 ** PWM11 +#define SERVO3_PIN 12 // PB6 ** Pin25 ** D12 +#define PS_ON_PIN 2 // X+ // PE4 ** Pin6 ** PWM2 **MUST BE HARDWARE PWM +#define FILWIDTH_PIN 15 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup! +#define FIL_RUNOUT_PIN 19 // Z+ // PD2 ** Pin45 ** USART1_RX #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 50 + #define RGB_LED_R_PIN 50 #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_G_PIN 51 + #define RGB_LED_G_PIN 51 #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_B_PIN 52 + #define RGB_LED_B_PIN 52 #endif #include "pins_MKS_BASE_common.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 985aa056b8..b769d655d6 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -30,30 +30,30 @@ #endif #define BOARD_INFO_NAME "MKS BASE 1.6" -#define MKS_BASE_VERSION 16 +#define MKS_BASE_VERSION 16 // // Servos // -#define SERVO1_PIN 12 // Digital 12 / Pin 25 +#define SERVO1_PIN 12 // Digital 12 / Pin 25 // // Omitted RAMPS pins // #ifndef SERVO2_PIN - #define SERVO2_PIN -1 + #define SERVO2_PIN -1 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN -1 + #define SERVO3_PIN -1 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN -1 + #define FILWIDTH_PIN -1 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN -1 + #define FIL_RUNOUT_PIN -1 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN -1 + #define PS_ON_PIN -1 #endif #include "pins_MKS_BASE_common.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h index e859310bf0..2d06171906 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h @@ -34,19 +34,19 @@ // Heaters / Fans // // Power outputs EFBF or EFBE - #define MOSFET_D_PIN 7 + #define MOSFET_D_PIN 7 // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #define SPINDLE_LASER_PWM_PIN 2 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 15 // Pullup! - #define SPINDLE_DIR_PIN 19 + #define SPINDLE_LASER_PWM_PIN 2 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 15 // Pullup! + #define SPINDLE_DIR_PIN 19 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 2 + #define CASE_LIGHT_PIN 2 #endif #endif @@ -54,22 +54,22 @@ // // Microstepping pins // -#if MKS_BASE_VERSION >= 14 // |===== 1.4 =====|===== 1.5+ =====| - #define X_MS1_PIN 5 // PE3 | Pin 5 | PWM5 | | D3 | SERVO2_PIN - #define X_MS2_PIN 6 // PH3 | Pin 15 | PWM6 | Pin 14 | D6 | SERVO1_PIN - #define Y_MS1_PIN 59 // PF5 | Pin 92 | A5 | | | - #define Y_MS2_PIN 58 // PF4 | Pin 93 | A4 | | | - #define Z_MS1_PIN 22 // PA0 | Pin 78 | D22 | | | - #define Z_MS2_PIN 39 // PG2 | Pin 70 | D39 | | | +#if MKS_BASE_VERSION >= 14 // |===== 1.4 =====|===== 1.5+ =====| + #define X_MS1_PIN 5 // PE3 | Pin 5 | PWM5 | | D3 | SERVO2_PIN + #define X_MS2_PIN 6 // PH3 | Pin 15 | PWM6 | Pin 14 | D6 | SERVO1_PIN + #define Y_MS1_PIN 59 // PF5 | Pin 92 | A5 | | | + #define Y_MS2_PIN 58 // PF4 | Pin 93 | A4 | | | + #define Z_MS1_PIN 22 // PA0 | Pin 78 | D22 | | | + #define Z_MS2_PIN 39 // PG2 | Pin 70 | D39 | | | #if MKS_BASE_VERSION == 14 - #define E0_MS1_PIN 64 // PK2 | Pin 87 | A10 | | | - #define E0_MS2_PIN 63 // PK1 | Pin 88 | A9 | | | + #define E0_MS1_PIN 64 // PK2 | Pin 87 | A10 | | | + #define E0_MS2_PIN 63 // PK1 | Pin 88 | A9 | | | #else - #define E0_MS1_PIN 63 // PK1 | | | Pin 86 | A9 | - #define E0_MS2_PIN 64 // PK2 | | | Pin 87 | A10 | + #define E0_MS1_PIN 63 // PK1 | | | Pin 86 | A9 | + #define E0_MS2_PIN 64 // PK2 | | | Pin 87 | A10 | #endif - #define E1_MS1_PIN 57 // PF3 | Pin 94 | A3 | Pin 93 | A3 | - #define E1_MS2_PIN 4 // PG5 | Pin 1 | PWM4 | | D4 | SERVO3_PIN + #define E1_MS1_PIN 57 // PF3 | Pin 94 | A3 | Pin 93 | A3 | + #define E1_MS2_PIN 4 // PG5 | Pin 1 | PWM4 | | D4 | SERVO3_PIN #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 82a2111810..c4c90ba6fa 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -40,7 +40,7 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 // // PSU / SERVO @@ -48,8 +48,8 @@ // If PSU_CONTROL is specified, always hijack Servo 3 // #if ENABLED(PSU_CONTROL) - #define SERVO3_PIN -1 - #define PS_ON_PIN 4 + #define SERVO3_PIN -1 + #define PS_ON_PIN 4 #endif #include "pins_RAMPS.h" @@ -104,44 +104,44 @@ // // orange/white SDCD - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 // white ENCA - #define BTN_EN1 35 + #define BTN_EN1 35 // green ENCB - #define BTN_EN2 37 + #define BTN_EN2 37 // purple ENCBTN - #define BTN_ENC 31 + #define BTN_ENC 31 // brown A0 - #define DOGLCD_A0 27 + #define DOGLCD_A0 27 // green/white LCS - #define DOGLCD_CS 29 + #define DOGLCD_CS 29 // 50 gray MISO // 51 yellow MOSI // 52 orange SCK // blue SDCS - //#define SDSS 53 + //#define SDSS 53 // // VIKI2 4-wire lead // // blue BTN - #define KILL_PIN 23 + #define KILL_PIN 23 // green BUZZER - #define BEEPER_PIN 25 + #define BEEPER_PIN 25 // yellow RED-LED - #define STAT_LED_RED_PIN 16 + #define STAT_LED_RED_PIN 16 // white BLUE-LED - #define STAT_LED_BLUE_PIN 17 + #define STAT_LED_BLUE_PIN 17 #endif diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h index d56bbd1e45..3236627c3b 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h @@ -35,7 +35,7 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 // // CS Pins wired to avoid conflict with the LCD @@ -43,47 +43,47 @@ // #ifndef X_CS_PIN - #define X_CS_PIN 63 + #define X_CS_PIN 63 #endif #ifndef Y_CS_PIN - #define Y_CS_PIN 64 + #define Y_CS_PIN 64 #endif #ifndef Z_CS_PIN - #define Z_CS_PIN 65 + #define Z_CS_PIN 65 #endif #ifndef E0_CS_PIN - #define E0_CS_PIN 66 + #define E0_CS_PIN 66 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN 21 + #define E1_CS_PIN 21 #endif // TMC2130 Diag Pins (currently just for reference) -#define X_DIAG_PIN 3 -#define Y_DIAG_PIN 14 -#define Z_DIAG_PIN 18 -#define E0_DIAG_PIN 2 -#define E1_DIAG_PIN 15 +#define X_DIAG_PIN 3 +#define Y_DIAG_PIN 14 +#define Z_DIAG_PIN 18 +#define E0_DIAG_PIN 2 +#define E1_DIAG_PIN 15 #ifndef SERVO1_PIN - #define SERVO1_PIN 12 + #define SERVO1_PIN 12 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN 39 + #define SERVO2_PIN 39 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 32 + #define SERVO3_PIN 32 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN 20 + #define E1_SERIAL_TX_PIN 20 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN 21 + #define E1_SERIAL_RX_PIN 21 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 272ff5636b..050932773e 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -66,19 +66,19 @@ // #ifndef SERVO0_PIN #ifdef IS_RAMPS_13 - #define SERVO0_PIN 7 + #define SERVO0_PIN 7 #else - #define SERVO0_PIN 11 + #define SERVO0_PIN 11 #endif #endif #ifndef SERVO1_PIN - #define SERVO1_PIN 6 + #define SERVO1_PIN 6 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN 5 + #define SERVO2_PIN 5 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 4 + #define SERVO3_PIN 4 #endif // @@ -86,26 +86,26 @@ // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN 3 + #define X_MIN_PIN 3 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN 2 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN 14 + #define Y_MIN_PIN 14 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 15 + #define Y_MAX_PIN 15 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN 18 + #define Z_MIN_PIN 18 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 19 + #define Z_MAX_PIN 19 #endif #endif @@ -113,67 +113,67 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN 53 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN 49 #endif #ifndef Z_STEP_PIN - #define Z_STEP_PIN 46 + #define Z_STEP_PIN 46 #endif -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN 40 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN 42 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN 44 #endif // // Temperature Sensors // #ifndef TEMP_0_PIN - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN 13 // Analog Input #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN 15 // Analog Input + #define TEMP_1_PIN 15 // Analog Input #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN 14 // Analog Input #endif // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -197,74 +197,74 @@ // Heaters / Fans // #ifndef MOSFET_D_PIN - #define MOSFET_D_PIN -1 + #define MOSFET_D_PIN -1 #endif #ifndef RAMPS_D8_PIN - #define RAMPS_D8_PIN 8 + #define RAMPS_D8_PIN 8 #endif #ifndef RAMPS_D9_PIN - #define RAMPS_D9_PIN 9 + #define RAMPS_D9_PIN 9 #endif #ifndef RAMPS_D10_PIN - #define RAMPS_D10_PIN 10 + #define RAMPS_D10_PIN 10 #endif -#define HEATER_0_PIN RAMPS_D10_PIN +#define HEATER_0_PIN RAMPS_D10_PIN -#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed - #define HEATER_BED_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan - #define HEATER_1_PIN RAMPS_D9_PIN -#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed - #define HEATER_1_PIN RAMPS_D9_PIN - #define HEATER_BED_PIN RAMPS_D8_PIN -#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan - #define FAN1_PIN RAMPS_D8_PIN -#elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") - #define HEATER_BED_PIN RAMPS_D8_PIN +#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed + #define HEATER_BED_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan + #define HEATER_1_PIN RAMPS_D9_PIN +#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed + #define HEATER_1_PIN RAMPS_D9_PIN + #define HEATER_BED_PIN RAMPS_D8_PIN +#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan + #define FAN1_PIN RAMPS_D8_PIN +#elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") + #define HEATER_BED_PIN RAMPS_D8_PIN #if HOTENDS == 1 - #define FAN1_PIN MOSFET_D_PIN + #define FAN1_PIN MOSFET_D_PIN #else - #define HEATER_1_PIN MOSFET_D_PIN + #define HEATER_1_PIN MOSFET_D_PIN #endif #endif #ifndef FAN_PIN #if EITHER(IS_RAMPS_EFB, IS_RAMPS_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN RAMPS_D9_PIN + #define FAN_PIN RAMPS_D9_PIN #elif EITHER(IS_RAMPS_EEF, IS_RAMPS_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN RAMPS_D8_PIN - #elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed - #define FAN_PIN 4 // IO pin. Buffer needed - #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN RAMPS_D9_PIN + #define FAN_PIN RAMPS_D8_PIN + #elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed + #define FAN_PIN 4 // IO pin. Buffer needed + #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") + #define FAN_PIN RAMPS_D9_PIN #endif #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS 53 +#define LED_PIN 13 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif // RAMPS 1.4 DIO 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 4 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) - #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #if NUM_SERVOS <= 1 // Prefer the servo connector + #define CASE_LIGHT_PIN 6 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN 44 // Hardware PWM #endif #endif @@ -272,14 +272,14 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) - #if !NUM_SERVOS // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #if !NUM_SERVOS // Use servo connector if possible + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_DIR_PIN 65 #else #error "No auto-assignable Spindle/Laser pins available." #endif @@ -290,13 +290,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 + #define TMC_SW_MOSI 66 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 + #define TMC_SW_MISO 44 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 + #define TMC_SW_SCK 64 #endif #endif @@ -307,11 +307,11 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial1 + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 //#define Z2_HARDWARE_SERIAL Serial1 //#define E0_HARDWARE_SERIAL Serial1 //#define E1_HARDWARE_SERIAL Serial1 @@ -324,91 +324,91 @@ // #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 40 + #define X_SERIAL_TX_PIN 40 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_RX_PIN 63 #endif #ifndef X2_SERIAL_TX_PIN - #define X2_SERIAL_TX_PIN -1 + #define X2_SERIAL_TX_PIN -1 #endif #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN -1 + #define X2_SERIAL_RX_PIN -1 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 59 + #define Y_SERIAL_TX_PIN 59 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 64 + #define Y_SERIAL_RX_PIN 64 #endif #ifndef Y2_SERIAL_TX_PIN - #define Y2_SERIAL_TX_PIN -1 + #define Y2_SERIAL_TX_PIN -1 #endif #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN -1 + #define Y2_SERIAL_RX_PIN -1 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 42 + #define Z_SERIAL_TX_PIN 42 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 65 + #define Z_SERIAL_RX_PIN 65 #endif #ifndef Z2_SERIAL_TX_PIN - #define Z2_SERIAL_TX_PIN -1 + #define Z2_SERIAL_TX_PIN -1 #endif #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN -1 + #define Z2_SERIAL_RX_PIN -1 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 44 + #define E0_SERIAL_TX_PIN 44 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 66 + #define E0_SERIAL_RX_PIN 66 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN -1 + #define E1_SERIAL_TX_PIN -1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 + #define E1_SERIAL_RX_PIN -1 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN -1 + #define E2_SERIAL_TX_PIN -1 #endif #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 + #define E2_SERIAL_RX_PIN -1 #endif #ifndef E3_SERIAL_TX_PIN - #define E3_SERIAL_TX_PIN -1 + #define E3_SERIAL_TX_PIN -1 #endif #ifndef E3_SERIAL_RX_PIN - #define E3_SERIAL_RX_PIN -1 + #define E3_SERIAL_RX_PIN -1 #endif #ifndef E4_SERIAL_TX_PIN - #define E4_SERIAL_TX_PIN -1 + #define E4_SERIAL_TX_PIN -1 #endif #ifndef E4_SERIAL_RX_PIN - #define E4_SERIAL_RX_PIN -1 + #define E4_SERIAL_RX_PIN -1 #endif #ifndef E5_SERIAL_TX_PIN - #define E5_SERIAL_TX_PIN -1 + #define E5_SERIAL_TX_PIN -1 #endif #ifndef E5_SERIAL_RX_PIN - #define E5_SERIAL_RX_PIN -1 + #define E5_SERIAL_RX_PIN -1 #endif #ifndef E6_SERIAL_TX_PIN - #define E6_SERIAL_TX_PIN -1 + #define E6_SERIAL_TX_PIN -1 #endif #ifndef E6_SERIAL_RX_PIN - #define E6_SERIAL_RX_PIN -1 + #define E6_SERIAL_RX_PIN -1 #endif #ifndef E7_SERIAL_TX_PIN - #define E7_SERIAL_TX_PIN -1 + #define E7_SERIAL_TX_PIN -1 #endif #ifndef E7_SERIAL_RX_PIN - #define E7_SERIAL_RX_PIN -1 + #define E7_SERIAL_RX_PIN -1 #endif #endif @@ -416,13 +416,13 @@ // Průša i3 MK2 Multiplexer Support // #ifndef E_MUX0_PIN - #define E_MUX0_PIN 40 // Z_CS_PIN + #define E_MUX0_PIN 40 // Z_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 42 // E0_CS_PIN + #define E_MUX1_PIN 42 // E0_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 44 // E1_CS_PIN + #define E_MUX2_PIN 44 // E1_CS_PIN #endif ////////////////////////// @@ -436,62 +436,62 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 65 - #define LCD_PINS_D5 66 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 64 + #define LCD_PINS_RS 40 + #define LCD_PINS_ENABLE 42 + #define LCD_PINS_D4 65 + #define LCD_PINS_D5 66 + #define LCD_PINS_D6 44 + #define LCD_PINS_D7 64 #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 25 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 25 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #endif #elif ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS 64 - #define LCD_PINS_ENABLE 44 - #define LCD_PINS_D4 63 - #define LCD_PINS_D5 40 - #define LCD_PINS_D6 42 - #define LCD_PINS_D7 65 + #define LCD_PINS_RS 64 + #define LCD_PINS_ENABLE 44 + #define LCD_PINS_D4 63 + #define LCD_PINS_D5 40 + #define LCD_PINS_D6 42 + #define LCD_PINS_D7 65 #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 25 // Set as output on init - #define LCD_PINS_RS 27 // Pull low for 1s to init + #define LCD_PINS_DC 25 // Set as output on init + #define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 17 - #define DOGLCD_SCK 23 - #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_CS 16 + #define DOGLCD_MOSI 17 + #define DOGLCD_SCK 23 + #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 29 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #endif #endif @@ -499,10 +499,10 @@ #if DISABLED(NEWPANEL) // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK 38 + //#define SHIFT_LD 42 + //#define SHIFT_OUT 40 + //#define SHIFT_EN 17 #endif #endif @@ -514,99 +514,99 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 17 - #define BTN_EN2 23 + #define BTN_EN1 17 + #define BTN_EN2 23 #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 31 + #define BTN_EN2 33 #endif - #define BTN_ENC 35 + #define BTN_ENC 35 #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #endif #ifndef KILL_PIN - #define KILL_PIN 41 + #define KILL_PIN 41 #endif #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 + #define LCD_BACKLIGHT_PIN 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS SDSS - #define KILL_PIN 41 + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS SDSS + #define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 40 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 42 - #define BTN_ENC -1 + #define BTN_EN1 40 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 42 + #define BTN_ENC -1 - #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 + #define LCD_SDSS SDSS + #define SD_DETECT_PIN 49 #elif ANY(VIKI2, miniVIKI) - #define DOGLCD_CS 45 - #define DOGLCD_A0 44 + #define DOGLCD_CS 45 + #define DOGLCD_A0 44 #define LCD_SCREEN_ROT_180 - #define BEEPER_PIN 33 - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define BEEPER_PIN 33 + #define STAT_LED_RED_PIN 32 + #define STAT_LED_BLUE_PIN 35 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - #define KILL_PIN 31 + #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board + #define KILL_PIN 31 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 - #define BEEPER_PIN 23 - #define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN 23 + #define LCD_BACKLIGHT_PIN 33 - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 - #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define LCD_SDSS SDSS + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) - #define BEEPER_PIN 37 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define BEEPER_PIN 37 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 #ifndef KILL_PIN - #define KILL_PIN 41 + #define KILL_PIN 41 #endif - #if ENABLED(MKS_MINI_12864) // Added in Marlin 1.1.6 + #if ENABLED(MKS_MINI_12864) // Added in Marlin 1.1.6 - #define DOGLCD_A0 27 - #define DOGLCD_CS 25 + #define DOGLCD_A0 27 + #define DOGLCD_CS 25 // GLCD features // Uncomment screen orientation @@ -615,50 +615,50 @@ //#define LCD_SCREEN_ROT_270 // not connected to a pin - #define LCD_BACKLIGHT_PIN -1 // 65 (MKS mini12864 can't adjust backlight by software!) + #define LCD_BACKLIGHT_PIN -1 // 65 (MKS mini12864 can't adjust backlight by software!) - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 31 + #define BTN_EN2 33 #elif ENABLED(FYSETC_MINI_12864) // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 - #define DOGLCD_A0 16 - #define DOGLCD_CS 17 + #define DOGLCD_A0 16 + #define DOGLCD_CS 17 - #define BTN_EN1 33 - #define BTN_EN2 31 + #define BTN_EN1 33 + #define BTN_EN2 31 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN 25 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN 27 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN 29 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN 25 #endif #endif #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // not connected to a pin - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 // GLCD features // Uncomment screen orientation @@ -666,16 +666,16 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 - #define SD_DETECT_PIN 49 - #define KILL_PIN 64 + #define SD_DETECT_PIN 49 + #define KILL_PIN 64 #elif ENABLED(ZONESTAR_LCD) - #define ADC_KEYPAD_PIN 12 + #define ADC_KEYPAD_PIN 12 #elif ENABLED(AZSMZ_12864) @@ -684,22 +684,22 @@ #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 #if ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #endif #endif @@ -708,16 +708,16 @@ #endif // HAS_SPI_LCD #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 #ifndef BTN_EN1 - #define BTN_EN1 64 + #define BTN_EN1 64 #endif #ifndef BTN_EN2 - #define BTN_EN2 59 + #define BTN_EN2 59 #endif #ifndef BTN_ENC - #define BTN_ENC 63 + #define BTN_ENC 63 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index ea2ace7e86..f6847feb4b 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -32,31 +32,31 @@ // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 -#define FIL_RUNOUT_PIN 2 +#define FIL_RUNOUT_PIN 2 #if NUM_RUNOUT_SENSORS > 1 - #define FIL_RUNOUT2_PIN 15 // Creality CR-X can use dual runout sensors + #define FIL_RUNOUT2_PIN 15 // Creality CR-X can use dual runout sensors #endif -#define SD_DETECT_PIN 49 // Always define onboard SD detect +#define SD_DETECT_PIN 49 // Always define onboard SD detect -#define PS_ON_PIN 40 // Used by CR2020 Industrial series +#define PS_ON_PIN 40 // Used by CR2020 Industrial series #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) - #define CASE_LIGHT_PIN 65 + #define CASE_LIGHT_PIN 65 #endif #include "pins_RAMPS.h" #ifndef BEEPER_PIN - #define BEEPER_PIN 37 // Always define beeper pin so Play Tone works with ExtUI + #define BEEPER_PIN 37 // Always define beeper pin so Play Tone works with ExtUI #endif -#define EXP1_PIN 65 // A11 - Used by CR2020 Industrial series for case -#define EXP2_PIN 66 // A12 -#define EXP3_PIN 11 // SERVO0_PIN -#define EXP4_PIN 12 // PS_ON_PIN +#define EXP1_PIN 65 // A11 - Used by CR2020 Industrial series for case +#define EXP2_PIN 66 // A12 +#define EXP3_PIN 11 // SERVO0_PIN +#define EXP4_PIN 12 // PS_ON_PIN -#define SUICIDE_PIN 12 // Used by CR2020 Industrial series -#define SUICIDE_PIN_INVERTING true // Used by CR2020 Industrial series +#define SUICIDE_PIN 12 // Used by CR2020 Industrial series +#define SUICIDE_PIN_INVERTING true // Used by CR2020 Industrial series diff --git a/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h b/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h index 39aecb0bc7..b0ba7822ef 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h @@ -27,12 +27,12 @@ #define BOARD_INFO_NAME "Dagoma3D F5 RAMPS" -#define X_STOP_PIN 2 -#define Y_STOP_PIN 3 -#define Z_STOP_PIN 15 -#define FIL_RUNOUT_PIN 39 +#define X_STOP_PIN 2 +#define Y_STOP_PIN 3 +#define Z_STOP_PIN 15 +#define FIL_RUNOUT_PIN 39 -#define ORIG_E0_AUTO_FAN_PIN 7 +#define ORIG_E0_AUTO_FAN_PIN 7 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index aa45370e6a..0323366944 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -37,80 +37,80 @@ // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 16 -#define Y_MAX_PIN 17 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN 3 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 16 +#define Y_MAX_PIN 17 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN 19 #endif // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 26 +#define X_DIR_PIN 28 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 38 -#define Y_DIR_PIN 40 -#define Y_ENABLE_PIN 36 +#define Y_STEP_PIN 38 +#define Y_DIR_PIN 40 +#define Y_ENABLE_PIN 36 -#define Z_STEP_PIN 44 -#define Z_DIR_PIN 46 -#define Z_ENABLE_PIN 42 +#define Z_STEP_PIN 44 +#define Z_DIR_PIN 46 +#define Z_ENABLE_PIN 42 -#define E0_STEP_PIN 32 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN 32 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 // // Temperature Sensors // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN 2 // Analog Input +#define TEMP_BED_PIN 1 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // #if ENABLED(RAMPS_V_1_0) - #define HEATER_0_PIN 12 - #define HEATER_BED_PIN -1 + #define HEATER_0_PIN 12 + #define HEATER_BED_PIN -1 #ifndef FAN_PIN - #define FAN_PIN 11 + #define FAN_PIN 11 #endif -#else // RAMPS_V_1_1 or RAMPS_V_1_2 - #define HEATER_0_PIN 10 - #define HEATER_BED_PIN 8 +#else // RAMPS_V_1_1 or RAMPS_V_1_2 + #define HEATER_0_PIN 10 + #define HEATER_BED_PIN 8 #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN 9 #endif #endif // // Misc. Functions // -#define SDPOWER_PIN 48 -#define SDSS 53 -#define LED_PIN 13 -#define CASE_LIGHT_PIN 45 // Hardware PWM +#define SDPOWER_PIN 48 +#define SDSS 53 +#define LED_PIN 13 +#define CASE_LIGHT_PIN 45 // Hardware PWM // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 41 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM -#define SPINDLE_DIR_PIN 43 +#define SPINDLE_LASER_ENA_PIN 41 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM +#define SPINDLE_DIR_PIN 43 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index 24aa7b9c90..f93b6dcc86 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -44,8 +44,8 @@ #define BOARD_INFO_NAME "RAMPS 1.4 Plus" -#define RAMPS_D8_PIN 10 -#define RAMPS_D10_PIN 8 +#define RAMPS_D8_PIN 10 +#define RAMPS_D10_PIN 8 #include "pins_RAMPS.h" @@ -60,13 +60,13 @@ #undef E1_DIR_PIN #undef E1_ENABLE_PIN -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 24 #undef X_CS_PIN #undef Y_CS_PIN @@ -77,10 +77,10 @@ #if ENABLED(ULTRA_LCD, REPRAPWORLD_GRAPHICAL_LCD, CR10_STOCKDISPLAY) && !BOTH(NEWPANEL, PANEL_ONE) #if DISABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306) #undef LCD_PINS_RS - #define LCD_PINS_RS 42 // 3DYMY boards pin 16 -> 42 + #define LCD_PINS_RS 42 // 3DYMY boards pin 16 -> 42 #undef LCD_PINS_ENABLE - #define LCD_PINS_ENABLE 44 // 3DYMY boards pin 17 -> 44 + #define LCD_PINS_ENABLE 44 // 3DYMY boards pin 17 -> 44 #endif #undef LCD_PINS_D7 - #define LCD_PINS_D7 53 // 3DYMY boards pin 29 -> 53 + #define LCD_PINS_D7 53 // 3DYMY boards pin 29 -> 53 #endif diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h index da6b6e4187..8e84281754 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h @@ -33,15 +33,15 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 // Z-MAX pin J14 End Stops + #define Z_MIN_PROBE_PIN 19 // Z-MAX pin J14 End Stops #endif // // MOSFET changes // -#define RAMPS_D9_PIN 8 // FAN (by default) -#define RAMPS_D10_PIN 9 // EXTRUDER 1 -#define MOSFET_D_PIN 12 // EXTRUDER 2 or FAN +#define RAMPS_D9_PIN 8 // FAN (by default) +#define RAMPS_D10_PIN 9 // EXTRUDER 1 +#define MOSFET_D_PIN 12 // EXTRUDER 2 or FAN #include "pins_RAMPS.h" @@ -52,18 +52,18 @@ #undef E0_STEP_PIN #undef E0_DIR_PIN #undef E0_ENABLE_PIN -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 #undef E1_STEP_PIN #undef E1_DIR_PIN #undef E1_ENABLE_PIN -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 24 -#define STEPPER_RESET_PIN 41 // Stepper drivers have a reset on RigidBot +#define STEPPER_RESET_PIN 41 // Stepper drivers have a reset on RigidBot // // Temperature Sensors @@ -71,33 +71,33 @@ #undef TEMP_0_PIN #undef TEMP_1_PIN #undef TEMP_BED_PIN -#define TEMP_0_PIN 14 // Analog Input -#define TEMP_1_PIN 13 // Analog Input -#define TEMP_BED_PIN 15 // Analog Input +#define TEMP_0_PIN 14 // Analog Input +#define TEMP_1_PIN 13 // Analog Input +#define TEMP_BED_PIN 15 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #undef MAX6675_SS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card + #define MAX6675_SS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card #else - #define MAX6675_SS_PIN 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present + #define MAX6675_SS_PIN 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present #endif // // Heaters / Fans // #undef HEATER_BED_PIN -#define HEATER_BED_PIN 10 +#define HEATER_BED_PIN 10 #ifndef FAN_PIN - #define FAN_PIN 8 // Same as RAMPS_13_EEF + #define FAN_PIN 8 // Same as RAMPS_13_EEF #endif // // Misc. Functions // #undef PS_ON_PIN -#define PS_ON_PIN -1 +#define PS_ON_PIN -1 // // LCD / Controller @@ -106,33 +106,33 @@ #if ENABLED(RIGIDBOT_PANEL) #undef BEEPER_PIN - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 // Direction buttons - #define BTN_UP 37 - #define BTN_DWN 35 - #define BTN_LFT 33 - #define BTN_RT 32 + #define BTN_UP 37 + #define BTN_DWN 35 + #define BTN_LFT 33 + #define BTN_RT 32 // 'R' button #undef BTN_ENC - #define BTN_ENC 31 + #define BTN_ENC 31 // Disable encoder #undef BTN_EN1 - #define BTN_EN1 -1 + #define BTN_EN1 -1 #undef BTN_EN2 - #define BTN_EN2 -1 + #define BTN_EN2 -1 #undef SD_DETECT_PIN - #define SD_DETECT_PIN 22 + #define SD_DETECT_PIN 22 #elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) #undef SD_DETECT_PIN - #define SD_DETECT_PIN 22 + #define SD_DETECT_PIN 22 #undef KILL_PIN - #define KILL_PIN 32 + #define KILL_PIN 32 #endif diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h index eb46ec9eaa..d56ab1bb7f 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h @@ -40,12 +40,12 @@ #define DAC_STEPPER_ORDER { 0, 1, 2, 3 } #define DAC_STEPPER_SENSE 0.05 // sense resistors on rigidboard stepper chips are .05 value -#define DAC_STEPPER_ADDRESS 0 -#define DAC_STEPPER_MAX 4096 // was 5000 but max allowable value is actually 4096 -#define DAC_STEPPER_VREF 1 // internal Vref, gain 2x = 4.096V -#define DAC_STEPPER_GAIN 1 // value of 1 here sets gain of 2 -#define DAC_DISABLE_PIN 42 // set low to enable DAC -#define DAC_OR_ADDRESS 0x01 +#define DAC_STEPPER_ADDRESS 0 +#define DAC_STEPPER_MAX 4096 // was 5000 but max allowable value is actually 4096 +#define DAC_STEPPER_VREF 1 // internal Vref, gain 2x = 4.096V +#define DAC_STEPPER_GAIN 1 // value of 1 here sets gain of 2 +#define DAC_DISABLE_PIN 42 // set low to enable DAC +#define DAC_OR_ADDRESS 0x01 #ifndef DAC_MOTOR_CURRENT_DEFAULT #define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis diff --git a/Marlin/src/pins/ramps/pins_RL200.h b/Marlin/src/pins/ramps/pins_RL200.h index 570a9c26f9..7b0303476b 100644 --- a/Marlin/src/pins/ramps/pins_RL200.h +++ b/Marlin/src/pins/ramps/pins_RL200.h @@ -37,16 +37,16 @@ #error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200." #endif -#define E0_STEP_PIN 26 // (RUMBA E1 pins) -#define E0_DIR_PIN 25 -#define E0_ENABLE_PIN 27 +#define E0_STEP_PIN 26 // (RUMBA E1 pins) +#define E0_DIR_PIN 25 +#define E0_ENABLE_PIN 27 -#define E1_STEP_PIN 29 // (RUMBA E2 pins) -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 39 +#define E1_STEP_PIN 29 // (RUMBA E2 pins) +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 39 -#define Z2_STEP_PIN 23 // (RUMBA E0 pins) -#define Z2_DIR_PIN 22 -#define Z2_ENABLE_PIN 24 +#define Z2_STEP_PIN 23 // (RUMBA E0 pins) +#define Z2_DIR_PIN 22 +#define Z2_ENABLE_PIN 24 #include "pins_RUMBA.h" diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index e613b9cb6c..4bf10d7399 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -41,56 +41,56 @@ // // Servos // -#define SERVO0_PIN 5 +#define SERVO0_PIN 5 // // Limit Switches // -#define X_MIN_PIN 37 -#define X_MAX_PIN 36 -#define Y_MIN_PIN 35 -#define Y_MAX_PIN 34 -#define Z_MIN_PIN 33 -#define Z_MAX_PIN 32 +#define X_MIN_PIN 37 +#define X_MAX_PIN 36 +#define Y_MIN_PIN 35 +#define Y_MAX_PIN 34 +#define Z_MIN_PIN 33 +#define Z_MAX_PIN 32 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 17 -#define X_DIR_PIN 16 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN 17 +#define X_DIR_PIN 16 +#define X_ENABLE_PIN 48 -#define Y_STEP_PIN 54 -#define Y_DIR_PIN 47 -#define Y_ENABLE_PIN 55 +#define Y_STEP_PIN 54 +#define Y_DIR_PIN 47 +#define Y_ENABLE_PIN 55 -#define Z_STEP_PIN 57 -#define Z_DIR_PIN 56 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 57 +#define Z_DIR_PIN 56 +#define Z_ENABLE_PIN 62 #ifndef E0_STEP_PIN - #define E0_STEP_PIN 23 - #define E0_DIR_PIN 22 - #define E0_ENABLE_PIN 24 + #define E0_STEP_PIN 23 + #define E0_DIR_PIN 22 + #define E0_ENABLE_PIN 24 #endif #ifndef E1_STEP_PIN - #define E1_STEP_PIN 26 - #define E1_DIR_PIN 25 - #define E1_ENABLE_PIN 27 + #define E1_STEP_PIN 26 + #define E1_DIR_PIN 25 + #define E1_ENABLE_PIN 27 #endif #if E1_STEP_PIN != 29 - #define E2_STEP_PIN 29 - #define E2_DIR_PIN 28 - #define E2_ENABLE_PIN 39 + #define E2_STEP_PIN 29 + #define E2_DIR_PIN 28 + #define E2_ENABLE_PIN 39 #endif // @@ -98,134 +98,134 @@ // #ifndef TEMP_0_PIN #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 6 // Analog Input (connector *K1* on RUMBA thermocouple ADD ON is used) + #define TEMP_0_PIN 6 // Analog Input (connector *K1* on RUMBA thermocouple ADD ON is used) #else - #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) + #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) #endif #endif #ifndef TEMP_1_PIN #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 5 // Analog Input (connector *K2* on RUMBA thermocouple ADD ON is used) + #define TEMP_1_PIN 5 // Analog Input (connector *K2* on RUMBA thermocouple ADD ON is used) #else - #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) + #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) #endif #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) + #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) #else - #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) + #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) #endif // Optional for extruder 4 or chamber: -//#define TEMP_X_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) +//#define TEMP_X_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) #ifndef TEMP_CHAMBER_PIN - //#define TEMP_CHAMBER_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) + //#define TEMP_CHAMBER_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) + #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) #else - #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) + #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) #endif // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_2_PIN 6 -#define HEATER_3_PIN 8 -#define HEATER_BED_PIN 9 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_2_PIN 6 +#define HEATER_3_PIN 8 +#define HEATER_BED_PIN 9 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN 7 #endif #ifndef FAN1_PIN - #define FAN1_PIN 8 + #define FAN1_PIN 8 #endif // // Misc. Functions // -#define LED_PIN 13 -#define PS_ON_PIN 45 -#define KILL_PIN 46 -#define CASE_LIGHT_PIN 45 +#define LED_PIN 13 +#define PS_ON_PIN 45 +#define KILL_PIN 46 +#define CASE_LIGHT_PIN 45 // // M3/M4/M5 - Spindle/Laser Control // #ifndef SPINDLE_LASER_PWM_PIN - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM. Pin 4 interrupts OC0* and OC1* always in use? + #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM. Pin 4 interrupts OC0* and OC1* always in use? #endif #ifndef SPINDLE_LASER_ENA_PIN - #define SPINDLE_LASER_ENA_PIN 14 // Pullup! + #define SPINDLE_LASER_ENA_PIN 14 // Pullup! #endif #ifndef SPINDLE_DIR_PIN - #define SPINDLE_DIR_PIN 15 + #define SPINDLE_DIR_PIN 15 #endif // // LCD / Controller // #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 38 // Set as output on init - #define LCD_PINS_RS 41 // Pull low for 1s to init + #define LCD_PINS_DC 38 // Set as output on init + #define LCD_PINS_RS 41 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 19 - #define DOGLCD_MOSI 42 - #define DOGLCD_SCK 18 - #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_CS 19 + #define DOGLCD_MOSI 42 + #define DOGLCD_SCK 18 + #define DOGLCD_A0 LCD_PINS_DC #elif ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS 42 - #define DOGLCD_A0 19 - #define DOGLCD_MOSI 51 - #define DOGLCD_SCK 52 + #define DOGLCD_CS 42 + #define DOGLCD_A0 19 + #define DOGLCD_MOSI 51 + #define DOGLCD_SCK 52 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 18 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN 18 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 41 + #define RGB_LED_R_PIN 41 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 38 + #define RGB_LED_G_PIN 38 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 40 + #define RGB_LED_B_PIN 40 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN 25 #endif #else - #define LCD_PINS_RS 19 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 18 - #define LCD_PINS_D5 38 - #define LCD_PINS_D6 41 + #define LCD_PINS_RS 19 + #define LCD_PINS_ENABLE 42 + #define LCD_PINS_D4 18 + #define LCD_PINS_D5 38 + #define LCD_PINS_D6 41 #endif -#define LCD_PINS_D7 40 +#define LCD_PINS_D7 40 // // Beeper, SD Card, Encoder // -#define BEEPER_PIN 44 +#define BEEPER_PIN 44 #if ENABLED(SDSUPPORT) - #define SDSS 53 - #define SD_DETECT_PIN 49 + #define SDSS 53 + #define SD_DETECT_PIN 49 #endif #if ENABLED(NEWPANEL) - #define BTN_EN1 11 - #define BTN_EN2 12 - #define BTN_ENC 43 + #define BTN_EN1 11 + #define BTN_EN2 12 + #define BTN_ENC 43 #endif diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index d3b7413fa2..221b30b0cb 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -27,24 +27,24 @@ #define BOARD_INFO_NAME "Tango" -#define FAN_PIN 8 -#define FAN1_PIN -1 +#define FAN_PIN 8 +#define FAN1_PIN -1 -#define ORIG_E0_AUTO_FAN_PIN 7 +#define ORIG_E0_AUTO_FAN_PIN 7 #ifndef TEMP_0_PIN #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 10 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) + #define TEMP_0_PIN 10 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) #else - #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) + #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) #endif #endif #ifndef TEMP_1_PIN #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 9 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) + #define TEMP_1_PIN 9 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) #else - #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) + #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index 1c5ea39279..dcf5ff5a0a 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -31,10 +31,10 @@ // Servos // #if MB(TRIGORILLA_14_11) - #define SERVO0_PIN 5 - #define SERVO1_PIN 4 - #define SERVO2_PIN 11 - #define SERVO3_PIN 6 + #define SERVO0_PIN 5 + #define SERVO1_PIN 4 + #define SERVO2_PIN 11 + #define SERVO3_PIN 6 #endif // @@ -42,48 +42,48 @@ // //#define ANYCUBIC_4_MAX_PRO_ENDSTOPS #if ENABLED(ANYCUBIC_4_MAX_PRO_ENDSTOPS) - #define X_MAX_PIN 43 - #define Y_MIN_PIN 19 + #define X_MAX_PIN 43 + #define Y_MIN_PIN 19 #endif // Labeled pins -#define TRIGORILLA_HEATER_BED_PIN 8 -#define TRIGORILLA_HEATER_0_PIN 10 -#define TRIGORILLA_HEATER_1_PIN 45 // Anycubic Kossel: Unused +#define TRIGORILLA_HEATER_BED_PIN 8 +#define TRIGORILLA_HEATER_0_PIN 10 +#define TRIGORILLA_HEATER_1_PIN 45 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan -#define TRIGORILLA_FAN1_PIN 7 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN2_PIN 44 // Anycubic Kossel: Hotend fan +#define TRIGORILLA_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan +#define TRIGORILLA_FAN1_PIN 7 // Anycubic Kossel: Unused +#define TRIGORILLA_FAN2_PIN 44 // Anycubic Kossel: Hotend fan // Remap MOSFET pins to common usages: -#define RAMPS_D10_PIN TRIGORILLA_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h +#define RAMPS_D10_PIN TRIGORILLA_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h -#if HOTENDS > 1 // EEF and EEB +#if HOTENDS > 1 // EEF and EEB #define RAMPS_D9_PIN TRIGORILLA_HEATER_1_PIN #if !TEMP_SENSOR_BED // EEF - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN #else // EEB - #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN - #define FAN_PIN TRIGORILLA_FAN0_PIN // Override pin 4 in pins_RAMPS.h + #define RAMPS_D8_PINTRIGORILLA_HEATER_BED_PIN + #define FAN_PIN TRIGORILLA_FAN0_PIN // Override pin 4 in pins_RAMPS.h #endif #elif TEMP_SENSOR_BED // EFB (Anycubic Kossel default) - #define RAMPS_D9_PIN TRIGORILLA_FAN0_PIN - #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN + #define RAMPS_D9_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D8_PINTRIGORILLA_HEATER_BED_PIN #else // EFF - #define RAMPS_D9_PIN TRIGORILLA_FAN1_PIN - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D9_PIN TRIGORILLA_FAN1_PIN + #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN #endif -#if HOTENDS > 1 || TEMP_SENSOR_BED // EEF, EEB, EFB - #define FAN1_PIN TRIGORILLA_FAN1_PIN +#if HOTENDS > 1 || TEMP_SENSOR_BED // EEF, EEB, EFB + #define FAN1_PIN TRIGORILLA_FAN1_PIN #endif -#define FAN2_PIN TRIGORILLA_FAN2_PIN -#define ORIG_E0_AUTO_FAN_PIN TRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config +#define FAN2_PIN TRIGORILLA_FAN2_PIN +#define ORIG_E0_AUTO_FAN_PINTRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config #include "pins_RAMPS.h" @@ -96,25 +96,25 @@ // LCD Display output pins #if BOTH(NEWPANEL, PANEL_ONE) #undef LCD_PINS_D6 - #define LCD_PINS_D6 57 + #define LCD_PINS_D6 57 #endif // LCD Display input pins #if ENABLED(NEWPANEL) #if ANY(VIKI2, miniVIKI) #undef DOGLCD_A0 - #define DOGLCD_A0 23 + #define DOGLCD_A0 23 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #undef BEEPER_PIN - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #undef LCD_BACKLIGHT_PIN - #define LCD_BACKLIGHT_PIN 67 + #define LCD_BACKLIGHT_PIN 67 #endif #elif ENABLED(MINIPANEL) #undef BEEPER_PIN - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #undef DOGLCD_A0 - #define DOGLCD_A0 42 + #define DOGLCD_A0 42 #endif #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 9fc53379d5..f5c79d0b57 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -34,70 +34,70 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN 12 -#define SERVO2_PIN 5 -#define SERVO3_PIN 4 +#define SERVO0_PIN 11 +#define SERVO1_PIN 12 +#define SERVO2_PIN 5 +#define SERVO3_PIN 4 // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN 3 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN SERVO3_PIN + #define Z_MIN_PROBE_PIN SERVO3_PIN #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 -#define X_CS_PIN 57 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 +#define X_CS_PIN 57 -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 -#define Y_CS_PIN 58 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 +#define Y_CS_PIN 58 -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 -#define Z_CS_PIN 53 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 +#define Z_CS_PIN 53 -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 -#define E0_CS_PIN 49 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 +#define E0_CS_PIN 49 -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 -#define E1_CS_PIN E0_CS_PIN +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 +#define E1_CS_PIN E0_CS_PIN -#define E2_STEP_PIN 63 -#define E2_DIR_PIN 22 -#define E2_ENABLE_PIN 59 -#define E2_CS_PIN E0_CS_PIN +#define E2_STEP_PIN 63 +#define E2_DIR_PIN 22 +#define E2_ENABLE_PIN 59 +#define E2_CS_PIN E0_CS_PIN -#define E3_STEP_PIN 32 -#define E3_DIR_PIN 40 -#define E3_ENABLE_PIN 39 -#define E3_CS_PIN E0_CS_PIN +#define E3_STEP_PIN 32 +#define E3_DIR_PIN 40 +#define E3_ENABLE_PIN 39 +#define E3_CS_PIN E0_CS_PIN -#define E4_STEP_PIN 43 -#define E4_DIR_PIN 42 -#define E4_ENABLE_PIN 47 -#define E4_CS_PIN E0_CS_PIN +#define E4_STEP_PIN 43 +#define E4_DIR_PIN 42 +#define E4_ENABLE_PIN 47 +#define E4_CS_PIN E0_CS_PIN #if HAS_TMC_UART /** @@ -122,34 +122,34 @@ // Software serial // - #define X_SERIAL_TX_PIN -1 // 59 - #define X_SERIAL_RX_PIN -1 // 63 - #define X2_SERIAL_TX_PIN -1 - #define X2_SERIAL_RX_PIN -1 + #define X_SERIAL_TX_PIN -1 // 59 + #define X_SERIAL_RX_PIN -1 // 63 + #define X2_SERIAL_TX_PIN -1 + #define X2_SERIAL_RX_PIN -1 - #define Y_SERIAL_TX_PIN -1 // 64 - #define Y_SERIAL_RX_PIN -1 // 40 - #define Y2_SERIAL_TX_PIN -1 - #define Y2_SERIAL_RX_PIN -1 + #define Y_SERIAL_TX_PIN -1 // 64 + #define Y_SERIAL_RX_PIN -1 // 40 + #define Y2_SERIAL_TX_PIN -1 + #define Y2_SERIAL_RX_PIN -1 - #define Z_SERIAL_TX_PIN -1 // 44 - #define Z_SERIAL_RX_PIN -1 // 42 - #define Z2_SERIAL_TX_PIN -1 - #define Z2_SERIAL_RX_PIN -1 + #define Z_SERIAL_TX_PIN -1 // 44 + #define Z_SERIAL_RX_PIN -1 // 42 + #define Z2_SERIAL_TX_PIN -1 + #define Z2_SERIAL_RX_PIN -1 - #define E0_SERIAL_TX_PIN -1 // 66 - #define E0_SERIAL_RX_PIN -1 // 65 - #define E1_SERIAL_TX_PIN -1 - #define E1_SERIAL_RX_PIN -1 - #define E2_SERIAL_TX_PIN -1 - #define E2_SERIAL_RX_PIN -1 - #define E3_SERIAL_TX_PIN -1 - #define E3_SERIAL_RX_PIN -1 - #define E4_SERIAL_TX_PIN -1 - #define E4_SERIAL_RX_PIN -1 - #define E5_SERIAL_RX_PIN -1 - #define E6_SERIAL_RX_PIN -1 - #define E7_SERIAL_RX_PIN -1 + #define E0_SERIAL_TX_PIN -1 // 66 + #define E0_SERIAL_RX_PIN -1 // 65 + #define E1_SERIAL_TX_PIN -1 + #define E1_SERIAL_RX_PIN -1 + #define E2_SERIAL_TX_PIN -1 + #define E2_SERIAL_RX_PIN -1 + #define E3_SERIAL_TX_PIN -1 + #define E3_SERIAL_RX_PIN -1 + #define E4_SERIAL_TX_PIN -1 + #define E4_SERIAL_RX_PIN -1 + #define E5_SERIAL_RX_PIN -1 + #define E6_SERIAL_RX_PIN -1 + #define E7_SERIAL_RX_PIN -1 #endif // @@ -170,16 +170,16 @@ // // Temperature Sensors // -#define TEMP_0_PIN 13 -#define TEMP_1_PIN 15 -#define TEMP_2_PIN 10 -#define TEMP_3_PIN 11 -#define TEMP_BED_PIN 14 +#define TEMP_0_PIN 13 +#define TEMP_1_PIN 15 +#define TEMP_2_PIN 10 +#define TEMP_3_PIN 11 +#define TEMP_BED_PIN 14 #if TEMP_SENSOR_CHAMBER > 0 - #define TEMP_CHAMBER_PIN 12 + #define TEMP_CHAMBER_PIN 12 #else - #define TEMP_4_PIN 12 + #define TEMP_4_PIN 12 #endif // SPI for Max6675 or Max31855 Thermocouple @@ -192,50 +192,50 @@ // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 44 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 7 +#define HEATER_2_PIN 44 +#define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN_PIN 9 #if EXTRUDERS >= 5 - #define HEATER_4_PIN 6 + #define HEATER_4_PIN 6 #else - #define FAN1_PIN 6 + #define FAN1_PIN 6 #endif #if EXTRUDERS >= 4 - #define HEATER_3_PIN 45 + #define HEATER_3_PIN 45 #else - #define FAN2_PIN 45 + #define FAN2_PIN 45 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS 53 +#define LED_PIN 13 //#ifndef FILWIDTH_PIN // #define FILWIDTH_PIN 5 // Analog Input //#endif // DIO 4 (Servos plug) for the runout sensor. -//#define FIL_RUNOUT_PIN SERVO3_PIN +//#define FIL_RUNOUT_PIN SERVO3_PIN #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif // // Case Light // #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN) - #if !NUM_SERVOS // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM - #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define CASE_LIGHT_PIN 44 // Hardware PWM + #if !NUM_SERVOS // Prefer the servo connector + #define CASE_LIGHT_PIN 6 // Hardware PWM + #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 + #define CASE_LIGHT_PIN 44 // Hardware PWM #endif #endif @@ -243,14 +243,14 @@ // M3/M4/M5 - Spindle/Laser Control // #if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE) - #if !NUM_SERVOS // Prefer the servo connector - #define SPINDLE_LASER_ENABLE_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 - #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define SPINDLE_LASER_ENABLE_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #if !NUM_SERVOS // Prefer the servo connector + #define SPINDLE_LASER_ENABLE_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_DIR_PIN 5 + #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 + #define SPINDLE_LASER_ENABLE_PIN 40 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_DIR_PIN 65 #endif #endif @@ -278,63 +278,63 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 65 - #define LCD_PINS_D5 66 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 64 + #define LCD_PINS_RS 40 + #define LCD_PINS_ENABLE 42 + #define LCD_PINS_D4 65 + #define LCD_PINS_D5 66 + #define LCD_PINS_D6 44 + #define LCD_PINS_D7 64 #elif ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS 64 - #define LCD_PINS_ENABLE 44 - #define LCD_PINS_D4 63 - #define LCD_PINS_D5 40 - #define LCD_PINS_D6 42 - #define LCD_PINS_D7 65 - #define ADC_KEYPAD_PIN 12 + #define LCD_PINS_RS 64 + #define LCD_PINS_ENABLE 44 + #define LCD_PINS_D4 63 + #define LCD_PINS_D5 40 + #define LCD_PINS_D6 42 + #define LCD_PINS_D7 65 + #define ADC_KEYPAD_PIN 12 #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 25 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 25 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #endif #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 25 // Set as output on init - #define LCD_PINS_RS 27 // Pull low for 1s to init + #define LCD_PINS_DC 25 // Set as output on init + #define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 17 - #define DOGLCD_SCK 23 - #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_CS 16 + #define DOGLCD_MOSI 17 + #define DOGLCD_SCK 23 + #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 29 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #endif #endif @@ -342,10 +342,10 @@ #if DISABLED(NEWPANEL) // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK 38 + //#define SHIFT_LD 42 + //#define SHIFT_OUT 40 + //#define SHIFT_EN 17 #endif #endif @@ -357,155 +357,155 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 17 - #define BTN_EN2 23 + #define BTN_EN1 17 + #define BTN_EN2 23 #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 31 + #define BTN_EN2 33 #endif - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 + //#define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 + #define LCD_BACKLIGHT_PIN 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - //#define KILL_PIN 41 + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS 53 + //#define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 + #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define LCD_SDSS 53 + #define SD_DETECT_PIN 49 #elif EITHER(VIKI2, miniVIKI) - #define DOGLCD_CS 45 - #define DOGLCD_A0 44 + #define DOGLCD_CS 45 + #define DOGLCD_A0 44 #define LCD_SCREEN_ROT_180 - #define BEEPER_PIN 33 - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define BEEPER_PIN 33 + #define STAT_LED_RED_PIN 32 + #define STAT_LED_BLUE_PIN 35 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - //#define KILL_PIN 31 + #define SDSS 53 + #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board + //#define KILL_PIN 31 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 - #define BEEPER_PIN 23 - #define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN 23 + #define LCD_BACKLIGHT_PIN 33 - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define LCD_SDSS 53 + #define SD_DETECT_PIN 49 + //#define KILL_PIN 41 #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 27 - #define DOGLCD_CS 25 + #define DOGLCD_A0 27 + #define DOGLCD_CS 25 // GLCD features - //#define LCD_CONTRAST_INIT 190 + //#define LCD_CONTRAST_INIT 190 // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - //#define SDSS 53 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 64 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 + //#define SDSS 53 + #define SD_DETECT_PIN 49 + //#define KILL_PIN 64 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // not connected to a pin - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 // GLCD features - //#define LCD_CONTRAST_INIT 190 + //#define LCD_CONTRAST_INIT 190 // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 - #define SDSS 53 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 64 + #define SDSS 53 + #define SD_DETECT_PIN 49 + //#define KILL_PIN 64 #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define SD_DETECT_PIN 49 + //#define KILL_PIN 41 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index 2af64bb2a0..776dfcc3da 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -44,97 +44,97 @@ // // Limit Switches // -#define X_STOP_PIN 22 -#define Y_STOP_PIN 26 -#define Z_STOP_PIN 29 +#define X_STOP_PIN 22 +#define Y_STOP_PIN 26 +#define Z_STOP_PIN 29 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Y_STEP_PIN 32 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN 32 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 31 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 36 -#define Z_ENABLE_PIN 34 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 36 +#define Z_ENABLE_PIN 34 -#define E0_STEP_PIN 42 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN 42 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 37 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 -#define MOTOR_CURRENT_PWM_XY_PIN 44 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 46 +#define MOTOR_CURRENT_PWM_XY_PIN 44 +#define MOTOR_CURRENT_PWM_Z_PIN 45 +#define MOTOR_CURRENT_PWM_E_PIN 46 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE - #define MOTOR_CURRENT_PWM_RANGE 2000 + #define MOTOR_CURRENT_PWM_RANGE 2000 #endif #define DEFAULT_PWM_MOTOR_CURRENT {1300, 1300, 1250} // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 9 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN 7 #endif -#define ORIG_E0_AUTO_FAN_PIN 77 +#define ORIG_E0_AUTO_FAN_PIN 77 // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 39 -#define LED_PIN 8 -#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered -#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. +#define SDSS 53 +#define SD_DETECT_PIN 39 +#define LED_PIN 8 +#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered +#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. // // LCD / Controller // -#define BEEPER_PIN 18 +#define BEEPER_PIN 18 -#define LCD_PINS_RS 20 -#define LCD_PINS_ENABLE 15 -#define LCD_PINS_D4 14 -#define LCD_PINS_D5 21 -#define LCD_PINS_D6 5 -#define LCD_PINS_D7 6 +#define LCD_PINS_RS 20 +#define LCD_PINS_ENABLE 15 +#define LCD_PINS_D4 14 +#define LCD_PINS_D5 21 +#define LCD_PINS_D6 5 +#define LCD_PINS_D7 6 // Buttons are directly attached -#define BTN_EN1 40 -#define BTN_EN2 41 -#define BTN_ENC 19 +#define BTN_EN1 40 +#define BTN_EN2 41 +#define BTN_ENC 19 // // M3/M4/M5 - Spindle/Laser Control // -#if HAS_CUTTER // use the LED_PIN for spindle speed control or case light +#if HAS_CUTTER // use the LED_PIN for spindle speed control or case light #undef LED_PIN - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENA_PIN 17 // Pullup! - #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #define SPINDLE_DIR_PIN 16 + #define SPINDLE_LASER_ENA_PIN 17 // Pullup! + #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM #else #undef LED_PIN - #define CASE_LIGHT_PIN 8 + #define CASE_LIGHT_PIN 8 #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index 8a48b07de7..8cc588a2f9 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -44,114 +44,114 @@ // // Servos // -#define SERVO0_PIN 11 +#define SERVO0_PIN 11 // // Limit Switches // -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN 32 +#define X_MIN_PIN 22 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 26 +#define Y_MAX_PIN 28 +#define Z_MIN_PIN 30 +#define Z_MAX_PIN 32 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN 37 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 35 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN 43 +#define E0_DIR_PIN 45 +#define E0_ENABLE_PIN 41 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 9 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN 7 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. -#define CASE_LIGHT_PIN 8 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 +#define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. +#define CASE_LIGHT_PIN 8 // // LCD / Controller // #if HAS_SPI_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN 18 #if ENABLED(NEWPANEL) - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 16 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 // Buttons directly attached - #define BTN_EN1 40 - #define BTN_EN2 42 - #define BTN_ENC 19 + #define BTN_EN1 40 + #define BTN_EN2 42 + #define BTN_ENC 19 - #define SD_DETECT_PIN 38 + #define SD_DETECT_PIN 38 - #else // !NEWPANEL - Old style panel with shift register + #else // !NEWPANEL - Old style panel with shift register // Buttons attached to a shift register - #define SHIFT_CLK 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK 38 + #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_EN 17 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 20 + #define LCD_PINS_D7 19 - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #endif // !NEWPANEL @@ -160,6 +160,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 10 // Pullup! -#define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header +#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN 10 // Pullup! +#define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index e128dc98d2..dc12442224 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -80,134 +80,134 @@ // Limit Switches // #if ENABLED(BOARD_REV_1_1_TO_1_3) - #define X_MIN_PIN 15 // SW1 - #define X_MAX_PIN 14 // SW2 - #define Y_MIN_PIN 17 // SW3 - #define Y_MAX_PIN 16 // SW4 - #define Z_MIN_PIN 19 // SW5 - #define Z_MAX_PIN 18 // SW6 + #define X_MIN_PIN 15 // SW1 + #define X_MAX_PIN 14 // SW2 + #define Y_MIN_PIN 17 // SW3 + #define Y_MAX_PIN 16 // SW4 + #define Z_MIN_PIN 19 // SW5 + #define Z_MAX_PIN 18 // SW6 #endif #if ENABLED(BOARD_REV_1_0) #if HAS_CUTTER - #define X_STOP_PIN 13 // SW1 (didn't change) - also has a useable hardware PWM - #define Y_STOP_PIN 12 // SW2 - #define Z_STOP_PIN 11 // SW3 + #define X_STOP_PIN 13 // SW1 (didn't change) - also has a useable hardware PWM + #define Y_STOP_PIN 12 // SW2 + #define Z_STOP_PIN 11 // SW3 #else - #define X_MIN_PIN 13 // SW1 - #define X_MAX_PIN 12 // SW2 - #define Y_MIN_PIN 11 // SW3 - #define Y_MAX_PIN 10 // SW4 - #define Z_MIN_PIN 9 // SW5 - #define Z_MAX_PIN 8 // SW6 + #define X_MIN_PIN 13 // SW1 + #define X_MAX_PIN 12 // SW2 + #define Y_MIN_PIN 11 // SW3 + #define Y_MAX_PIN 10 // SW4 + #define Z_MIN_PIN 9 // SW5 + #define Z_MAX_PIN 8 // SW6 #endif #endif #if ENABLED(BOARD_REV_1_5) - #define X_MIN_PIN 22 - #define X_MAX_PIN 24 - #define Y_MIN_PIN 26 - #define Y_MAX_PIN 28 - #define Z_MIN_PIN 30 - #define Z_MAX_PIN 32 + #define X_MIN_PIN 22 + #define X_MAX_PIN 24 + #define Y_MIN_PIN 26 + #define Y_MAX_PIN 28 + #define Z_MIN_PIN 30 + #define Z_MAX_PIN 32 #endif // // Z Probe (when not Z_MIN_PIN) // #if !defined(Z_MIN_PROBE_PIN) && !(HAS_CUTTER && ENABLED(BOARD_REV_1_0)) - #define Z_MIN_PROBE_PIN Z_MAX_PIN + #define Z_MIN_PROBE_PIN Z_MAX_PIN #endif // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN 37 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 35 #if HAS_CUTTER && ENABLED(BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 // Move E0 to the spare and get Spindle/Laser signals from E0 - #define E0_STEP_PIN 49 - #define E0_DIR_PIN 47 - #define E0_ENABLE_PIN 48 + #define E0_STEP_PIN 49 + #define E0_DIR_PIN 47 + #define E0_ENABLE_PIN 48 #else - #define E0_STEP_PIN 43 - #define E0_DIR_PIN 45 - #define E0_ENABLE_PIN 41 + #define E0_STEP_PIN 43 + #define E0_DIR_PIN 45 + #define E0_ENABLE_PIN 41 - #define E1_STEP_PIN 49 - #define E1_DIR_PIN 47 - #define E1_ENABLE_PIN 48 + #define E1_STEP_PIN 49 + #define E1_DIR_PIN 47 + #define E1_ENABLE_PIN 48 #endif // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 1 // Analog Input +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -//#define HEATER_1_PIN 3 // used for case light Rev A said "1" -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 2 +//#define HEATER_1_PIN 3 // used for case light Rev A said "1" +#define HEATER_BED_PIN 4 // // LCD / Controller // #if ANY(BOARD_REV_1_0, BOARD_REV_1_1_TO_1_3) - #define LCD_PINS_RS 24 - #define LCD_PINS_ENABLE 22 - #define LCD_PINS_D4 36 - #define LCD_PINS_D5 34 - #define LCD_PINS_D6 32 - #define LCD_PINS_D7 30 + #define LCD_PINS_RS 24 + #define LCD_PINS_ENABLE 22 + #define LCD_PINS_D4 36 + #define LCD_PINS_D5 34 + #define LCD_PINS_D6 32 + #define LCD_PINS_D7 30 #elif ENABLED(BOARD_REV_1_5, ULTRA_LCD) - #define BEEPER_PIN 18 + #define BEEPER_PIN 18 #if ENABLED(NEWPANEL) - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 16 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 // Buttons directly attached - #define BTN_EN1 40 - #define BTN_EN2 42 - #define BTN_ENC 19 + #define BTN_EN1 40 + #define BTN_EN2 42 + #define BTN_ENC 19 - #define SD_DETECT_PIN 38 + #define SD_DETECT_PIN 38 - #else // !NEWPANEL - Old style panel with shift register + #else // !NEWPANEL - Old style panel with shift register // Buttons attached to a shift register - #define SHIFT_CLK 38 - #define SHIFT_LD 42 - #define SHIFT_OUT 40 - #define SHIFT_EN 17 + #define SHIFT_CLK 38 + #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_EN 17 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 20 + #define LCD_PINS_D7 19 #endif // !NEWPANEL @@ -217,17 +217,17 @@ // case light - see spindle section for more info on available hardware PWMs // #if !PIN_EXISTS(CASE_LIGHT) && ENABLED(BOARD_REV_1_5) - #define CASE_LIGHT_PIN 7 // use PWM - MUST BE HARDWARE PWM + #define CASE_LIGHT_PIN 7 // use PWM - MUST BE HARDWARE PWM #endif // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if EITHER(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions - #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") - #define SPINDLE_LASER_PWM_PIN 9 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM - #define SPINDLE_LASER_ENA_PIN 8 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! + #if EITHER(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions + #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") + #define SPINDLE_LASER_PWM_PIN 9 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENA_PIN 8 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! #elif ENABLED(BOARD_REV_1_1_TO_1_3) /** * Only four hardware PWMs physically connected to anything on these boards: @@ -241,14 +241,14 @@ * They have an LED and resistor pullup to +24V which could damage 3.3V-5V ICs. */ #if EXTRUDERS == 1 - #define SPINDLE_DIR_PIN 43 - #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 41 // Pullup! - #elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available + #define SPINDLE_DIR_PIN 43 + #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 41 // Pullup! + #elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available #undef HEATER_BED_PIN - #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - Special precautions usually needed. - #define SPINDLE_LASER_ENA_PIN 40 // Pullup! (Probably pin 6 on the 10-pin + #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket + #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - Special precautions usually needed. + #define SPINDLE_LASER_ENA_PIN 40 // Pullup! (Probably pin 6 on the 10-pin // connector closest to the E0 socket) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_VORON.h b/Marlin/src/pins/ramps/pins_VORON.h index a6cb05928a..12c0a36db1 100644 --- a/Marlin/src/pins/ramps/pins_VORON.h +++ b/Marlin/src/pins/ramps/pins_VORON.h @@ -28,7 +28,7 @@ #define BOARD_INFO_NAME "VORON Design v2" -#define RAMPS_D8_PIN 11 +#define RAMPS_D8_PIN 11 #include "pins_RAMPS.h" @@ -36,10 +36,10 @@ // Heaters / Fans // #undef FAN_PIN -#define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. -#define CONTROLLER_FAN_PIN 8 -#define ORIG_E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan -#define ORIG_E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) +#define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. +#define CONTROLLER_FAN_PIN 8 +#define ORIG_E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan +#define ORIG_E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) // // LCDs and Controllers diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V20.h b/Marlin/src/pins/ramps/pins_ZRIB_V20.h index 450ad1f825..5aee07c96f 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V20.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V20.h @@ -28,24 +28,24 @@ #include "pins_MKS_GEN_13.h" -#define ZRIB_V20_D6_PIN 6 // Fan -#define ZRIB_V20_D9_PIN 9 // Fan2 -#define ZRIB_V20_A10_PIN 10 -#define ZRIB_V20_D16_PIN 16 -#define ZRIB_V20_D17_PIN 17 -#define ZRIB_V20_D23_PIN 23 -#define ZRIB_V20_D25_PIN 25 -#define ZRIB_V20_D27_PIN 27 -#define ZRIB_V20_D29_PIN 29 -#define ZRIB_V20_D37_PIN 37 +#define ZRIB_V20_D6_PIN 6 // Fan +#define ZRIB_V20_D9_PIN 9 // Fan2 +#define ZRIB_V20_A10_PIN 10 +#define ZRIB_V20_D16_PIN 16 +#define ZRIB_V20_D17_PIN 17 +#define ZRIB_V20_D23_PIN 23 +#define ZRIB_V20_D25_PIN 25 +#define ZRIB_V20_D27_PIN 27 +#define ZRIB_V20_D29_PIN 29 +#define ZRIB_V20_D37_PIN 37 -#define ORIG_E0_AUTO_FAN_PIN ZRIB_V20_D6_PIN -#define ORIG_E1_AUTO_FAN_PIN ZRIB_V20_D6_PIN -#define ORIG_E2_AUTO_FAN_PIN ZRIB_V20_D6_PIN -#define ORIG_E3_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#define ORIG_E0_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#define ORIG_E1_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#define ORIG_E2_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#define ORIG_E3_AUTO_FAN_PIN ZRIB_V20_D6_PIN #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 11 // Analog Input + #define FILWIDTH_PIN 11 // Analog Input #endif #if ENABLED(ZONESTAR_LCD) @@ -58,12 +58,12 @@ #undef ADC_KEYPAD_PIN #undef BEEPER_PIN - #define LCD_PINS_RS ZRIB_V20_D16_PIN - #define LCD_PINS_ENABLE ZRIB_V20_D17_PIN - #define LCD_PINS_D4 ZRIB_V20_D23_PIN - #define LCD_PINS_D5 ZRIB_V20_D25_PIN - #define LCD_PINS_D6 ZRIB_V20_D27_PIN - #define LCD_PINS_D7 ZRIB_V20_D29_PIN - #define ADC_KEYPAD_PIN ZRIB_V20_A10_PIN - #define BEEPER_PIN ZRIB_V20_D37_PIN + #define LCD_PINS_RS ZRIB_V20_D16_PIN + #define LCD_PINS_ENABLE ZRIB_V20_D17_PIN + #define LCD_PINS_D4 ZRIB_V20_D23_PIN + #define LCD_PINS_D5 ZRIB_V20_D25_PIN + #define LCD_PINS_D6 ZRIB_V20_D27_PIN + #define LCD_PINS_D7 ZRIB_V20_D29_PIN + #define ADC_KEYPAD_PIN ZRIB_V20_A10_PIN + #define BEEPER_PIN ZRIB_V20_D37_PIN #endif diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 9808646d32..f55ec51567 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -37,129 +37,129 @@ // Servos // #ifndef SERVO0_PIN - #define SERVO0_PIN 11 + #define SERVO0_PIN 11 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 4 + #define SERVO3_PIN 4 #endif // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN 3 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN 2 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN -1 + #define X_CS_PIN -1 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN -1 + #define Y_CS_PIN -1 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 #ifndef Z_CS_PIN - #define Z_CS_PIN -1 + #define Z_CS_PIN -1 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN -1 + #define E0_CS_PIN -1 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 #ifndef E1_CS_PIN - #define E1_CS_PIN -1 + #define E1_CS_PIN -1 #endif // Red -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 40 -#define E2_ENABLE_PIN 65 +#define E2_STEP_PIN 42 +#define E2_DIR_PIN 40 +#define E2_ENABLE_PIN 65 #ifndef E2_CS_PIN - #define E2_CS_PIN -1 + #define E2_CS_PIN -1 #endif // Black -#define E3_STEP_PIN 44 -#define E3_DIR_PIN 64 -#define E3_ENABLE_PIN 66 +#define E3_STEP_PIN 44 +#define E3_DIR_PIN 64 +#define E3_ENABLE_PIN 66 #ifndef E3_CS_PIN - #define E3_CS_PIN -1 + #define E3_CS_PIN -1 #endif // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_2_PIN 5 // Analog Input (BLACK) -#define TEMP_3_PIN 9 // Analog Input (RED) -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN 13 // Analog Input +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_2_PIN 5 // Analog Input (BLACK) +#define TEMP_3_PIN 9 // Analog Input (RED) +#define TEMP_BED_PIN 14 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 6 -#define HEATER_3_PIN 5 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 7 +#define HEATER_2_PIN 6 +#define HEATER_3_PIN 5 +#define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN_PIN 9 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS 53 +#define LED_PIN 13 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif // Оn the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 4 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) - #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #if NUM_SERVOS <= 1 // Prefer the servo connector + #define CASE_LIGHT_PIN 6 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN 44 // Hardware PWM #endif #endif @@ -167,14 +167,14 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) - #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_DIR_PIN 65 #endif #endif @@ -183,13 +183,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 + #define TMC_SW_MOSI 66 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 + #define TMC_SW_MISO 44 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 + #define TMC_SW_SCK 64 #endif #endif @@ -217,90 +217,90 @@ // #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 40 + #define X_SERIAL_TX_PIN 40 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_RX_PIN 63 #endif #ifndef X2_SERIAL_TX_PIN - #define X2_SERIAL_TX_PIN -1 + #define X2_SERIAL_TX_PIN -1 #endif #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN -1 + #define X2_SERIAL_RX_PIN -1 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 59 + #define Y_SERIAL_TX_PIN 59 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 64 + #define Y_SERIAL_RX_PIN 64 #endif #ifndef Y2_SERIAL_TX_PIN - #define Y2_SERIAL_TX_PIN -1 + #define Y2_SERIAL_TX_PIN -1 #endif #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN -1 + #define Y2_SERIAL_RX_PIN -1 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 42 + #define Z_SERIAL_TX_PIN 42 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 65 + #define Z_SERIAL_RX_PIN 65 #endif #ifndef Z2_SERIAL_TX_PIN - #define Z2_SERIAL_TX_PIN -1 + #define Z2_SERIAL_TX_PIN -1 #endif #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN -1 + #define Z2_SERIAL_RX_PIN -1 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 44 + #define E0_SERIAL_TX_PIN 44 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 66 + #define E0_SERIAL_RX_PIN 66 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN -1 + #define E1_SERIAL_TX_PIN -1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 + #define E1_SERIAL_RX_PIN -1 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN -1 + #define E2_SERIAL_TX_PIN -1 #endif #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 + #define E2_SERIAL_RX_PIN -1 #endif #ifndef E3_SERIAL_TX_PIN - #define E3_SERIAL_TX_PIN -1 + #define E3_SERIAL_TX_PIN -1 #endif #ifndef E3_SERIAL_RX_PIN - #define E3_SERIAL_RX_PIN -1 + #define E3_SERIAL_RX_PIN -1 #endif #ifndef E4_SERIAL_TX_PIN - #define E4_SERIAL_TX_PIN -1 + #define E4_SERIAL_TX_PIN -1 #endif #ifndef E4_SERIAL_RX_PIN - #define E4_SERIAL_RX_PIN -1 + #define E4_SERIAL_RX_PIN -1 #endif #ifndef E5_SERIAL_TX_PIN - #define E5_SERIAL_TX_PIN -1 + #define E5_SERIAL_TX_PIN -1 #endif #ifndef E5_SERIAL_RX_PIN - #define E5_SERIAL_RX_PIN -1 + #define E5_SERIAL_RX_PIN -1 #endif #ifndef E6_SERIAL_TX_PIN - #define E6_SERIAL_TX_PIN -1 + #define E6_SERIAL_TX_PIN -1 #endif #ifndef E6_SERIAL_RX_PIN - #define E6_SERIAL_RX_PIN -1 + #define E6_SERIAL_RX_PIN -1 #endif #ifndef E7_SERIAL_TX_PIN - #define E7_SERIAL_TX_PIN -1 + #define E7_SERIAL_TX_PIN -1 #endif #ifndef E7_SERIAL_RX_PIN - #define E7_SERIAL_RX_PIN -1 + #define E7_SERIAL_RX_PIN -1 #endif #endif diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index 3a38e5ce16..61c2e1b494 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -81,55 +81,55 @@ A stepper for E0 extruder // // Servos // -#define SERVO0_PIN 61 // Analog pin 7, Digital pin 61 +#define SERVO0_PIN 61 // Analog pin 7, Digital pin 61 // // Limit Switches // -#define X_MIN_PIN 9 -#define Y_MIN_PIN 10 -#define Z_MIN_PIN 11 +#define X_MIN_PIN 9 +#define Y_MIN_PIN 10 +#define Z_MIN_PIN 11 -#define Z_MIN_PROBE_PIN 62 // Analog pin 8, Digital pin 62 +#define Z_MIN_PROBE_PIN 62 // Analog pin 8, Digital pin 62 // // Steppers // -#define X_STEP_PIN 2 -#define X_DIR_PIN 5 -#define X_ENABLE_PIN 8 +#define X_STEP_PIN 2 +#define X_DIR_PIN 5 +#define X_ENABLE_PIN 8 -#define Y_STEP_PIN 3 -#define Y_DIR_PIN 6 -#define Y_ENABLE_PIN 8 +#define Y_STEP_PIN 3 +#define Y_DIR_PIN 6 +#define Y_ENABLE_PIN 8 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 7 -#define Z_ENABLE_PIN 8 +#define Z_STEP_PIN 4 +#define Z_DIR_PIN 7 +#define Z_ENABLE_PIN 8 -#define E0_STEP_PIN 12 -#define E0_DIR_PIN 13 -#define E0_ENABLE_PIN 8 +#define E0_STEP_PIN 12 +#define E0_DIR_PIN 13 +#define E0_ENABLE_PIN 8 // // Heaters / Fans // -#define HEATER_0_PIN 55 // "Hold": Analog pin 1, Digital pin 55 -#define HEATER_BED_PIN 57 // "CoolEn": Analog pin 3, Digital pin 57 -#define FAN_PIN 54 // "Abort": Analog pin 0, Digital pin 54 +#define HEATER_0_PIN 55 // "Hold": Analog pin 1, Digital pin 55 +#define HEATER_BED_PIN 57 // "CoolEn": Analog pin 3, Digital pin 57 +#define FAN_PIN 54 // "Abort": Analog pin 0, Digital pin 54 #undef E0_AUTO_FAN_PIN -#define E0_AUTO_FAN_PIN 56 // "Resume": Analog pin 2, Digital pin 56 +#define E0_AUTO_FAN_PIN 56 // "Resume": Analog pin 2, Digital pin 56 // // Temperature Sensors // -#define TEMP_0_PIN 4 // "SDA": Analog pin 4, Digital pin 58 -#define TEMP_BED_PIN 5 // "SCL": Analog pin 5, Digital pin 59 +#define TEMP_0_PIN 4 // "SDA": Analog pin 4, Digital pin 58 +#define TEMP_BED_PIN 5 // "SCL": Analog pin 5, Digital pin 59 // // Misc. Functions // -#define SDSS 52 +#define SDSS 52 #if ENABLED(ZONESTAR_LCD) @@ -160,13 +160,13 @@ A stepper for E0 extruder // // LCD / Controller // - #define LCD_PINS_ENABLE 14 - #define LCD_PINS_RS 15 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 17 - #define LCD_PINS_D6 18 - #define LCD_PINS_D7 19 - #define ADC_KEYPAD_PIN 6 //60 // Analog pin 6, Digital pin 60 + #define LCD_PINS_ENABLE 14 + #define LCD_PINS_RS 15 + #define LCD_PINS_D4 16 + #define LCD_PINS_D5 17 + #define LCD_PINS_D6 18 + #define LCD_PINS_D7 19 + #define ADC_KEYPAD_PIN 6 //60 // Analog pin 6, Digital pin 60 /** * The below defines will scale all the values to work properly on both diff --git a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h index 619d7f62c7..8b035e8876 100644 --- a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h +++ b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h @@ -35,126 +35,126 @@ // // Servos // -#define SERVO0_PIN 36 -#define SERVO1_PIN 40 -#define SERVO2_PIN 41 -#define SERVO3_PIN -1 +#define SERVO0_PIN 36 +#define SERVO1_PIN 40 +#define SERVO2_PIN 41 +#define SERVO3_PIN -1 // // Limit Switches // -#define X_MIN_PIN 33 // PC1 -#define X_MAX_PIN 34 // PC2 -#define Y_MIN_PIN 35 // PC3 -#define Y_MAX_PIN 37 // PC5 -#define Z_MIN_PIN 38 // PC6 -#define Z_MAX_PIN 39 // PC7 +#define X_MIN_PIN 33 // PC1 +#define X_MAX_PIN 34 // PC2 +#define Y_MIN_PIN 35 // PC3 +#define Y_MAX_PIN 37 // PC5 +#define Z_MIN_PIN 38 // PC6 +#define Z_MAX_PIN 39 // PC7 // // Steppers // -#define X_STEP_PIN 96 // PB24 -#define X_DIR_PIN 2 // PB25 -#define X_ENABLE_PIN 24 // PA15, motor RESET pin +#define X_STEP_PIN 96 // PB24 +#define X_DIR_PIN 2 // PB25 +#define X_ENABLE_PIN 24 // PA15, motor RESET pin -#define Y_STEP_PIN 94 // PB22 -#define Y_DIR_PIN 95 // PB23 -#define Y_ENABLE_PIN 24 // PA15, motor RESET pin +#define Y_STEP_PIN 94 // PB22 +#define Y_DIR_PIN 95 // PB23 +#define Y_ENABLE_PIN 24 // PA15, motor RESET pin -#define Z_STEP_PIN 98 // PC27 -#define Z_DIR_PIN 3 // PC28 -#define Z_ENABLE_PIN 24 // PA15, motor RESET pin +#define Z_STEP_PIN 98 // PC27 +#define Z_DIR_PIN 3 // PC28 +#define Z_ENABLE_PIN 24 // PA15, motor RESET pin -#define E0_STEP_PIN 5 // PC25 -#define E0_DIR_PIN 4 // PC26 -#define E0_ENABLE_PIN 24 // PA15, motor RESET pin +#define E0_STEP_PIN 5 // PC25 +#define E0_DIR_PIN 4 // PC26 +#define E0_ENABLE_PIN 24 // PA15, motor RESET pin -#define E1_STEP_PIN 28 // PD3 on piggy -#define E1_DIR_PIN 27 // PD2 on piggy -#define E1_ENABLE_PIN 24 // PA15, motor RESET pin +#define E1_STEP_PIN 28 // PD3 on piggy +#define E1_DIR_PIN 27 // PD2 on piggy +#define E1_ENABLE_PIN 24 // PA15, motor RESET pin -#define E2_STEP_PIN 11 // PD7 on piggy -#define E2_DIR_PIN 29 // PD6 on piggy -#define E2_ENABLE_PIN 24 // PA15, motor RESET pin +#define E2_STEP_PIN 11 // PD7 on piggy +#define E2_DIR_PIN 29 // PD6 on piggy +#define E2_ENABLE_PIN 24 // PA15, motor RESET pin -#define E3_STEP_PIN 30 // PD9 on piggy -#define E3_DIR_PIN 12 // PD8 on piggy -#define E3_ENABLE_PIN 24 // PA15, motor RESET pin +#define E3_STEP_PIN 30 // PD9 on piggy +#define E3_DIR_PIN 12 // PD8 on piggy +#define E3_ENABLE_PIN 24 // PA15, motor RESET pin // Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 99 // PC10 -#define Y_MS1_PIN 10 // PC29 -#define Z_MS1_PIN 44 // PC19 -#define E0_MS1_PIN 45 // PC18 +#define X_MS1_PIN 99 // PC10 +#define Y_MS1_PIN 10 // PC29 +#define Z_MS1_PIN 44 // PC19 +#define E0_MS1_PIN 45 // PC18 -//#define MOTOR_FAULT_PIN 22 // PB26 , motor X-Y-Z-E0 motor FAULT +//#define MOTOR_FAULT_PIN 22 // PB26 , motor X-Y-Z-E0 motor FAULT // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input (PA24) -#define TEMP_1_PIN 2 // Analog Input (PA23 on piggy) -#define TEMP_2_PIN 3 // Analog Input (PA22 on piggy) -#define TEMP_3_PIN 4 // Analog Input (PA6 on piggy) -#define TEMP_BED_PIN 0 // Analog Input (PA16) +#define TEMP_0_PIN 1 // Analog Input (PA24) +#define TEMP_1_PIN 2 // Analog Input (PA23 on piggy) +#define TEMP_2_PIN 3 // Analog Input (PA22 on piggy) +#define TEMP_3_PIN 4 // Analog Input (PA6 on piggy) +#define TEMP_BED_PIN 0 // Analog Input (PA16) // // Heaters / Fans // // Note that on the Due pin A0 on the board is channel 2 on the ARM chip -#define HEATER_0_PIN 68 // PA1 -#define HEATER_1_PIN 8 // PC22 on piggy -#define HEATER_2_PIN 9 // PC21 on piggy -#define HEATER_3_PIN 97 // PC20 on piggy -#define HEATER_BED_PIN 69 // PA0 +#define HEATER_0_PIN 68 // PA1 +#define HEATER_1_PIN 8 // PC22 on piggy +#define HEATER_2_PIN 9 // PC21 on piggy +#define HEATER_3_PIN 97 // PC20 on piggy +#define HEATER_BED_PIN 69 // PA0 #ifndef FAN_PIN - #define FAN_PIN 92 // PA5 + #define FAN_PIN 92 // PA5 #endif -#define FAN1_PIN 31 // PA7 +#define FAN1_PIN 31 // PA7 // // Misc. Functions // -#define SDSS 77 // PA28 -#define SD_DETECT_PIN 87 // PA29 -#define LED_RED_PIN 40 // PC8 -#define LED_GREEN_PIN 41 // PC9 +#define SDSS 77 // PA28 +#define SD_DETECT_PIN 87 // PA29 +#define LED_RED_PIN 40 // PC8 +#define LED_GREEN_PIN 41 // PC9 -#define EXP_VOLTAGE_LEVEL_PIN 65 +#define EXP_VOLTAGE_LEVEL_PIN 65 -#define SPI_CHAN_DAC 1 +#define SPI_CHAN_DAC 1 -#define DAC0_SYNC 53 // PB14 -#define DAC1_SYNC 6 // PC24 +#define DAC0_SYNC 53 // PB14 +#define DAC1_SYNC 6 // PC24 // 64K SPI EEPROM #define SPI_EEPROM -#define SPI_CHAN_EEPROM1 2 -#define SPI_EEPROM1_CS 25 // PD0 +#define SPI_CHAN_EEPROM1 2 +#define SPI_EEPROM1_CS 25 // PD0 // 2K SPI EEPROM -#define SPI_EEPROM2_CS 26 // PD1 +#define SPI_EEPROM2_CS 26 // PD1 // FLASH SPI // 32Mb -#define SPI_FLASH_CS 23 // PA14 +#define SPI_FLASH_CS 23 // PA14 // // LCD / Controller // #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS 18 - #define LCD_PINS_ENABLE 15 - #define LCD_PINS_D4 19 - #define BEEPER_PIN 64 + #define LCD_PINS_RS 18 + #define LCD_PINS_ENABLE 15 + #define LCD_PINS_D4 19 + #define BEEPER_PIN 64 - #define BTN_EN1 14 - #define BTN_EN2 16 - #define BTN_ENC 17 + #define BTN_EN1 14 + #define BTN_EN2 16 + #define BTN_ENC 17 #undef UI_VOLTAGE_LEVEL - #define UI_VOLTAGE_LEVEL 1 + #define UI_VOLTAGE_LEVEL 1 #endif // REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER diff --git a/Marlin/src/pins/sam/pins_ARCHIM1.h b/Marlin/src/pins/sam/pins_ARCHIM1.h index ddc9f407ec..606e024697 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM1.h +++ b/Marlin/src/pins/sam/pins_ARCHIM1.h @@ -46,7 +46,7 @@ // // Timers // -#define STEP_TIMER_NUM 3 +#define STEP_TIMER_NUM 3 #define HAL_STEP_TIMER_ISR() void TC3_Handler() // @@ -56,147 +56,145 @@ // // Servos // -#define SERVO0_PIN 20 // D20 PB12 (Header J20 20) -#define SERVO1_PIN 21 // D21 PB13 (Header J20 19) - +#define SERVO0_PIN 20 // D20 PB12 (Header J20 20) +#define SERVO1_PIN 21 // D21 PB13 (Header J20 19) // // Limit Switches // -#define X_MIN_PIN 14 // PD4 MIN ES1 -#define X_MAX_PIN 32 // PD10 MAX ES1 -#define Y_MIN_PIN 29 // PD6 MIN ES2 -#define Y_MAX_PIN 15 // PD5 MAX ES2 -#define Z_MIN_PIN 31 // PA7 MIN ES3 -#define Z_MAX_PIN 30 // PD9 MAX ES3 +#define X_MIN_PIN 14 // PD4 MIN ES1 +#define X_MAX_PIN 32 // PD10 MAX ES1 +#define Y_MIN_PIN 29 // PD6 MIN ES2 +#define Y_MAX_PIN 15 // PD5 MAX ES2 +#define Z_MIN_PIN 31 // PA7 MIN ES3 +#define Z_MAX_PIN 30 // PD9 MAX ES3 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 66 // D66 PB15 (Header J20 15) + #define FIL_RUNOUT_PIN 66 // D66 PB15 (Header J20 15) #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN 67 // D67 PB16 (Header J20 16) + #define FIL_RUNOUT2_PIN 67 // D67 PB16 (Header J20 16) #endif - // // Steppers // -#define X_STEP_PIN 40 // PC8 STEP1 * -#define X_DIR_PIN 59 // PA4 DIR1 * -#define X_ENABLE_PIN 41 // PC9 EN1 +#define X_STEP_PIN 40 // PC8 STEP1 * +#define X_DIR_PIN 59 // PA4 DIR1 * +#define X_ENABLE_PIN 41 // PC9 EN1 -#define Y_STEP_PIN 49 // PC14 STEP2 * -#define Y_DIR_PIN 47 // PC16 DIR2 * -#define Y_ENABLE_PIN 48 // PC15 EN2 * +#define Y_STEP_PIN 49 // PC14 STEP2 * +#define Y_DIR_PIN 47 // PC16 DIR2 * +#define Y_ENABLE_PIN 48 // PC15 EN2 * -#define Z_STEP_PIN 36 // PC4 STEP Z * -#define Z_DIR_PIN 107 // PB10 DIR Z * -#define Z_ENABLE_PIN 96 // PC10 EN Z -AddOns * +#define Z_STEP_PIN 36 // PC4 STEP Z * +#define Z_DIR_PIN 107 // PB10 DIR Z * +#define Z_ENABLE_PIN 96 // PC10 EN Z -AddOns * -#define E0_STEP_PIN 78 // PB23 STEP3 * -#define E0_DIR_PIN 22 // PB26 DIR3 * -#define E0_ENABLE_PIN 97 // PB24 EN3 -Addons * +#define E0_STEP_PIN 78 // PB23 STEP3 * +#define E0_DIR_PIN 22 // PB26 DIR3 * +#define E0_ENABLE_PIN 97 // PB24 EN3 -Addons * -#define E1_STEP_PIN 26 // PD1 STEP4 * -#define E1_DIR_PIN 27 // PD2 DIR4 * -#define E1_ENABLE_PIN 28 // PD3 EN4 * +#define E1_STEP_PIN 26 // PD1 STEP4 * +#define E1_DIR_PIN 27 // PD2 DIR4 * +#define E1_ENABLE_PIN 28 // PD3 EN4 * // Microstepping mode pins * -#define X_MS1_PIN 39 // PC7 MOD0E1 - As listed in schematic -#define X_MS2_PIN 38 // PC6 MOD1E1 -#define X_MS3_PIN 37 // PC5 MOD2E1 +#define X_MS1_PIN 39 // PC7 MOD0E1 - As listed in schematic +#define X_MS2_PIN 38 // PC6 MOD1E1 +#define X_MS3_PIN 37 // PC5 MOD2E1 -#define Y_MS1_PIN 50 // PC13 MODE0E2 -#define Y_MS2_PIN 51 // PC12 MODE1E2 -#define Y_MS3_PIN 92 // PC11 MODE2E2 - AddOns +#define Y_MS1_PIN 50 // PC13 MODE0E2 +#define Y_MS2_PIN 51 // PC12 MODE1E2 +#define Y_MS3_PIN 92 // PC11 MODE2E2 - AddOns -#define Z_MS1_PIN 44 // PC19 MOD0E Z -#define Z_MS2_PIN 45 // PC18 MOD1E Z -#define Z_MS3_PIN 46 // PC17 MOD2E Z +#define Z_MS1_PIN 44 // PC19 MOD0E Z +#define Z_MS2_PIN 45 // PC18 MOD1E Z +#define Z_MS3_PIN 46 // PC17 MOD2E Z -#define E0_MS1_PIN 105 // PB22 MOD0E3 - AddOns -#define E0_MS2_PIN 106 // PC27 MOD1E3 - AddOns -#define E0_MS3_PIN 104 // PC20 MOD2E3 - AddOns +#define E0_MS1_PIN 105 // PB22 MOD0E3 - AddOns +#define E0_MS2_PIN 106 // PC27 MOD1E3 - AddOns +#define E0_MS3_PIN 104 // PC20 MOD2E3 - AddOns -#define E1_MS1_PIN 25 // PD0 MOD0E4 -#define E1_MS2_PIN 18 // PA11 MOD1E4 -#define E1_MS3_PIN 19 // PA10 MOD2E4 +#define E1_MS1_PIN 25 // PD0 MOD0E4 +#define E1_MS2_PIN 18 // PA11 MOD1E4 +#define E1_MS3_PIN 19 // PA10 MOD2E4 // Motor current PWM pins * -#define MOTOR_CURRENT_PWM_X_PIN 58 // PA6 X-REF TIOB2 -#define MOTOR_CURRENT_PWM_Y_PIN 12 // PD8 Y-REF TIOB8 -#define MOTOR_CURRENT_PWM_Z_PIN 10 // PC29 Z-REF TIOB7 -#define MOTOR_CURRENT_PWM_E0_PIN 3 // PC28 E1-REF TIOA7 -#define MOTOR_CURRENT_PWM_E1_PIN 11 // PD7 E2-REF TIOA8 +#define MOTOR_CURRENT_PWM_X_PIN 58 // PA6 X-REF TIOB2 +#define MOTOR_CURRENT_PWM_Y_PIN 12 // PD8 Y-REF TIOB8 +#define MOTOR_CURRENT_PWM_Z_PIN 10 // PC29 Z-REF TIOB7 +#define MOTOR_CURRENT_PWM_E0_PIN 3 // PC28 E1-REF TIOA7 +#define MOTOR_CURRENT_PWM_E1_PIN 11 // PD7 E2-REF TIOA8 -#define MOTOR_CURRENT_PWM_RANGE 2750 // (3.3 Volts * 100000 Ohms) / (100000 Ohms + 20000 Ohms) = 2.75 Volts (max vref) +#define MOTOR_CURRENT_PWM_RANGE 2750 // (3.3 Volts * 100000 Ohms) / (100000 Ohms + 20000 Ohms) = 2.75 Volts (max vref) #define DEFAULT_PWM_MOTOR_CURRENT { 1000, 1000, 1000 } //, 1000, 1000} // X Y Z E0 E1, 1000 = 1000mAh // // Temperature Sensors // -#define TEMP_0_PIN 10 // D10 PB19 THERM AN1 * -#define TEMP_1_PIN 9 // D9 PB18 THERM AN2 * -#define TEMP_2_PIN 8 // D8 PB17 THERM AN4 * -#define TEMP_BED_PIN 11 // D11 PB20 THERM AN3 * +#define TEMP_0_PIN 10 // D10 PB19 THERM AN1 * +#define TEMP_1_PIN 9 // D9 PB18 THERM AN2 * +#define TEMP_2_PIN 8 // D8 PB17 THERM AN4 * +#define TEMP_BED_PIN 11 // D11 PB20 THERM AN3 * // // Heaters / Fans // -#define HEATER_0_PIN 6 // D6 PC24 FET_PWM3 -#define HEATER_1_PIN 7 // D7 PC23 FET_PWM4 -#define HEATER_2_PIN 8 // D8 PC22 FET_PWM5 -#define HEATER_BED_PIN 9 // D9 PC21 BED_PWM +#define HEATER_0_PIN 6 // D6 PC24 FET_PWM3 +#define HEATER_1_PIN 7 // D7 PC23 FET_PWM4 +#define HEATER_2_PIN 8 // D8 PC22 FET_PWM5 +#define HEATER_BED_PIN 9 // D9 PC21 BED_PWM #ifndef FAN_PIN - #define FAN_PIN 4 // D4 PC26 FET_PWM1 + #define FAN_PIN 4 // D4 PC26 FET_PWM1 #endif -#define FAN1_PIN 5 // D5 PC25 FET_PWM2 +#define FAN1_PIN 5 // D5 PC25 FET_PWM2 // // Misc. Functions // // Internal MicroSD card reader on the PCB -#define INT_SCK_PIN 42 // D42 PA19/MCCK -#define INT_MISO_PIN 43 // D43 PA20/MCCDA -#define INT_MOSI_PIN 73 // D73 PA21/MCDA0 -#define INT_SDSS 55 // D55 PA24/MCDA3 +#define INT_SCK_PIN 42 // D42 PA19/MCCK +#define INT_MISO_PIN 43 // D43 PA20/MCCDA +#define INT_MOSI_PIN 73 // D73 PA21/MCDA0 +#define INT_SDSS 55 // D55 PA24/MCDA3 // External SD card reader on SC2 -#define SCK_PIN 76 // D76 PA27 -#define MISO_PIN 74 // D74 PA25 -#define MOSI_PIN 75 // D75 PA26 -#define SDSS 87 // D87 PA29 +#define SCK_PIN 76 // D76 PA27 +#define MISO_PIN 74 // D74 PA25 +#define MOSI_PIN 75 // D75 PA26 +#define SDSS 87 // D87 PA29 // 2MB SPI Flash -#define SPI_FLASH_SS 52 // D52 PB21 +#define SPI_FLASH_SS 52 // D52 PB21 // // LCD / Controller // #if HAS_SPI_LCD - #define BEEPER_PIN 23 // D24 PA15_CTS1 - #define LCD_PINS_RS 17 // D17 PA12_RXD1 - #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 - #define LCD_PINS_D4 69 // D69 PA0_CANTX0 - #define LCD_PINS_D5 54 // D54 PA16_SCK1 - #define LCD_PINS_D6 68 // D68 PA1_CANRX0 - #define LCD_PINS_D7 34 // D34 PC2_PWML0 + #define BEEPER_PIN 23 // D24 PA15_CTS1 + #define LCD_PINS_RS 17 // D17 PA12_RXD1 + #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 + #define LCD_PINS_D4 69 // D69 PA0_CANTX0 + #define LCD_PINS_D5 54 // D54 PA16_SCK1 + #define LCD_PINS_D6 68 // D68 PA1_CANRX0 + #define LCD_PINS_D7 34 // D34 PC2_PWML0 - #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 + #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 #if ENABLED(NEWPANEL) // Buttons on AUX-2 - #define BTN_EN1 60 // D60 PA3_TIOB1 - #define BTN_EN2 13 // D13 PB27_TIOB0 - #define BTN_ENC 16 // D16 PA13_TXD1 + #define BTN_EN1 60 // D60 PA3_TIOB1 + #define BTN_EN2 13 // D13 PB27_TIOB0 + #define BTN_ENC 16 // D16 PA13_TXD1 #endif // NEWPANEL #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index acd515d8c1..d2114ea433 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -52,8 +52,8 @@ // // Servos // -#define SERVO0_PIN 20 // D20 PB12 (Header J20 20) -#define SERVO1_PIN 21 // D21 PB13 (Header J20 19) +#define SERVO0_PIN 20 // D20 PB12 (Header J20 20) +#define SERVO1_PIN 21 // D21 PB13 (Header J20 19) // // Limit Switches @@ -65,83 +65,83 @@ // Otherwise use a physical endstop based configuration. // TMC2130 Diag Pins - #define X_DIAG_PIN 59 // PA4 - #define Y_DIAG_PIN 48 // PC15 - #define Z_DIAG_PIN 36 // PC4 - #define E0_DIAG_PIN 78 // PB23 - #define E1_DIAG_PIN 25 // PD0 + #define X_DIAG_PIN 59 // PA4 + #define Y_DIAG_PIN 48 // PC15 + #define Z_DIAG_PIN 36 // PC4 + #define E0_DIAG_PIN 78 // PB23 + #define E1_DIAG_PIN 25 // PD0 #if X_HOME_DIR < 0 - #define X_MIN_PIN X_DIAG_PIN - #define X_MAX_PIN 32 + #define X_MIN_PIN X_DIAG_PIN + #define X_MAX_PIN 32 #else - #define X_MIN_PIN 14 - #define X_MAX_PIN X_DIAG_PIN + #define X_MIN_PIN 14 + #define X_MAX_PIN X_DIAG_PIN #endif #if Y_HOME_DIR < 0 - #define Y_MIN_PIN Y_DIAG_PIN - #define Y_MAX_PIN 15 + #define Y_MIN_PIN Y_DIAG_PIN + #define Y_MAX_PIN 15 #else - #define Y_MIN_PIN 29 - #define Y_MAX_PIN Y_DIAG_PIN + #define Y_MIN_PIN 29 + #define Y_MAX_PIN Y_DIAG_PIN #endif #else - #define X_MIN_PIN 14 // PD4 MIN ES1 - #define X_MAX_PIN 32 // PD10 MAX ES1 - #define Y_MIN_PIN 29 // PD6 MIN ES2 - #define Y_MAX_PIN 15 // PD5 MAX ES2 + #define X_MIN_PIN 14 // PD4 MIN ES1 + #define X_MAX_PIN 32 // PD10 MAX ES1 + #define Y_MIN_PIN 29 // PD6 MIN ES2 + #define Y_MAX_PIN 15 // PD5 MAX ES2 #endif -#define Z_MIN_PIN 31 // PA7 MIN ES3 -#define Z_MAX_PIN 30 // PD9 MAX ES3 +#define Z_MIN_PIN 31 // PA7 MIN ES3 +#define Z_MAX_PIN 30 // PD9 MAX ES3 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 #endif // // Steppers // -#define X_STEP_PIN 38 // PC6 X-STEP * -#define X_DIR_PIN 37 // PC5 X-DIR * -#define X_ENABLE_PIN 41 // PC9 EN1 +#define X_STEP_PIN 38 // PC6 X-STEP * +#define X_DIR_PIN 37 // PC5 X-DIR * +#define X_ENABLE_PIN 41 // PC9 EN1 #ifndef X_CS_PIN - #define X_CS_PIN 39 // PC7 X_nCS + #define X_CS_PIN 39 // PC7 X_nCS #endif -#define Y_STEP_PIN 51 // PC12 Y-STEP * -#define Y_DIR_PIN 92 // PC11 Y-DIR -AddOns * -#define Y_ENABLE_PIN 49 // PC14 Y-EN * +#define Y_STEP_PIN 51 // PC12 Y-STEP * +#define Y_DIR_PIN 92 // PC11 Y-DIR -AddOns * +#define Y_ENABLE_PIN 49 // PC14 Y-EN * #ifndef Y_CS_PIN - #define Y_CS_PIN 50 // PC13 Y_nCS + #define Y_CS_PIN 50 // PC13 Y_nCS #endif -#define Z_STEP_PIN 46 // PC17 Z-STEP * -#define Z_DIR_PIN 47 // PC16 Z-DIR * -#define Z_ENABLE_PIN 44 // PC19 Z-END * +#define Z_STEP_PIN 46 // PC17 Z-STEP * +#define Z_DIR_PIN 47 // PC16 Z-DIR * +#define Z_ENABLE_PIN 44 // PC19 Z-END * #ifndef Z_CS_PIN - #define Z_CS_PIN 45 // PC18 Z_nCS + #define Z_CS_PIN 45 // PC18 Z_nCS #endif -#define E0_STEP_PIN 107 // PB10 E1-STEP -AddOns * -#define E0_DIR_PIN 96 // PC10 E1-DIR -AddOns * -#define E0_ENABLE_PIN 105 // PB22 E1-EN -AddOns * +#define E0_STEP_PIN 107 // PB10 E1-STEP -AddOns * +#define E0_DIR_PIN 96 // PC10 E1-DIR -AddOns * +#define E0_ENABLE_PIN 105 // PB22 E1-EN -AddOns * #ifndef E0_CS_PIN - #define E0_CS_PIN 104 // PC20 E1_nCS -AddOns * + #define E0_CS_PIN 104 // PC20 E1_nCS -AddOns * #endif -#define E1_STEP_PIN 22 // PB26 E2_STEP * -#define E1_DIR_PIN 97 // PB24 E2_DIR -AddOns * -#define E1_ENABLE_PIN 18 // PA11 E2-EN +#define E1_STEP_PIN 22 // PB26 E2_STEP * +#define E1_DIR_PIN 97 // PB24 E2_DIR -AddOns * +#define E1_ENABLE_PIN 18 // PA11 E2-EN #ifndef E1_CS_PIN - #define E1_CS_PIN 19 // PA10 E2_nCS + #define E1_CS_PIN 19 // PA10 E2_nCS #endif // @@ -150,106 +150,106 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 28 // PD3 + #define TMC_SW_MOSI 28 // PD3 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO 26 // PD1 + #define TMC_SW_MISO 26 // PD1 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK 27 // PD2 + #define TMC_SW_SCK 27 // PD2 #endif #endif // // Temperature Sensors // -#define TEMP_0_PIN 10 // D10 PB19 THERM AN1 * -#define TEMP_1_PIN 9 // D9 PB18 THERM AN2 * -#define TEMP_2_PIN 8 // D8 PB17 THERM AN4 * -#define TEMP_BED_PIN 11 // D11 PB20 THERM AN3 * +#define TEMP_0_PIN 10 // D10 PB19 THERM AN1 * +#define TEMP_1_PIN 9 // D9 PB18 THERM AN2 * +#define TEMP_2_PIN 8 // D8 PB17 THERM AN4 * +#define TEMP_BED_PIN 11 // D11 PB20 THERM AN3 * // // Heaters / Fans // -#define HEATER_0_PIN 6 // D6 PC24 FET_PWM3 -#define HEATER_1_PIN 7 // D7 PC23 FET_PWM4 -#define HEATER_2_PIN 8 // D8 PC22 FET_PWM5 -#define HEATER_BED_PIN 9 // D9 PC21 BED_PWM +#define HEATER_0_PIN 6 // D6 PC24 FET_PWM3 +#define HEATER_1_PIN 7 // D7 PC23 FET_PWM4 +#define HEATER_2_PIN 8 // D8 PC22 FET_PWM5 +#define HEATER_BED_PIN 9 // D9 PC21 BED_PWM #ifndef FAN_PIN - #define FAN_PIN 4 // D4 PC26 FET_PWM1 + #define FAN_PIN 4 // D4 PC26 FET_PWM1 #endif -#define FAN1_PIN 5 // D5 PC25 FET_PWM2 +#define FAN1_PIN 5 // D5 PC25 FET_PWM2 // // Misc. Functions // // Internal MicroSD card reader on the PCB -#define INT_SCK_PIN 42 // D42 PA19/MCCK -#define INT_MISO_PIN 43 // D43 PA20/MCCDA -#define INT_MOSI_PIN 73 // D73 PA21/MCDA0 -#define INT_SDSS 55 // D55 PA24/MCDA3 +#define INT_SCK_PIN 42 // D42 PA19/MCCK +#define INT_MISO_PIN 43 // D43 PA20/MCCDA +#define INT_MOSI_PIN 73 // D73 PA21/MCDA0 +#define INT_SDSS 55 // D55 PA24/MCDA3 // External SD card reader on SC2 -#define SCK_PIN 76 // D76 PA27 -#define MISO_PIN 74 // D74 PA25 -#define MOSI_PIN 75 // D75 PA26 -#define SDSS 87 // D87 PA29 +#define SCK_PIN 76 // D76 PA27 +#define MISO_PIN 74 // D74 PA25 +#define MOSI_PIN 75 // D75 PA26 +#define SDSS 87 // D87 PA29 // Unused Digital GPIO J20 Pins -#define GPIO_PB1_J20_5 94 // D94 PB1 (Header J20 5) -#define GPIO_PB0_J20_6 95 // D95 PB0 (Header J20 6) -#define GPIO_PB3_J20_7 103 // D103 PB3 (Header J20 7) -#define GPIO_PB2_J20_8 93 // D93 PB2 (Header J20 8) -#define GPIO_PB6_J20_9 99 // D99 PB6 (Header J20 9) -#define GPIO_PB5_J20_10 101 // D101 PB5 (Header J20 10) -#define GPIO_PB8_J20_11 100 // D100 PB8 (Header J20 11) -#define GPIO_PB4_J20_12 102 // D102 PB4 (Header J20 12) -#define GPIO_PB9_J20_13 108 // D108 PB9 (Header J20 13) -#define GPIO_PB7_J20_14 98 // D98 PB7 (Header J20 14) -#define GPIO_PB15_J20_15 66 // D66 PB15 (Header J20 15) -#define GPIO_PB16_J20_16 67 // D67 PB16 (Header J20 16) -#define GPIO_PB14_J20_17 53 // D53 PB14 (Header J20 17) -#define GPIO_PA18_J20_21 71 // D71 PA17 (Header J20 21) -#define GPIO_PA17_J20_22 70 // D70 PA17 (Header J20 22) +#define GPIO_PB1_J20_5 94 // D94 PB1 (Header J20 5) +#define GPIO_PB0_J20_6 95 // D95 PB0 (Header J20 6) +#define GPIO_PB3_J20_7 103 // D103 PB3 (Header J20 7) +#define GPIO_PB2_J20_8 93 // D93 PB2 (Header J20 8) +#define GPIO_PB6_J20_9 99 // D99 PB6 (Header J20 9) +#define GPIO_PB5_J20_10 101 // D101 PB5 (Header J20 10) +#define GPIO_PB8_J20_11 100 // D100 PB8 (Header J20 11) +#define GPIO_PB4_J20_12 102 // D102 PB4 (Header J20 12) +#define GPIO_PB9_J20_13 108 // D108 PB9 (Header J20 13) +#define GPIO_PB7_J20_14 98 // D98 PB7 (Header J20 14) +#define GPIO_PB15_J20_15 66 // D66 PB15 (Header J20 15) +#define GPIO_PB16_J20_16 67 // D67 PB16 (Header J20 16) +#define GPIO_PB14_J20_17 53 // D53 PB14 (Header J20 17) +#define GPIO_PA18_J20_21 71 // D71 PA17 (Header J20 21) +#define GPIO_PA17_J20_22 70 // D70 PA17 (Header J20 22) // Case Light -#define CASE_LIGHT_PIN GPIO_PB1_J20_5 +#define CASE_LIGHT_PIN GPIO_PB1_J20_5 // 2MB SPI Flash -#define SPI_FLASH_SS 52 // D52 PB21 +#define SPI_FLASH_SS 52 // D52 PB21 // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN GPIO_PB15_J20_15 + #define FIL_RUNOUT_PIN GPIO_PB15_J20_15 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN GPIO_PB16_J20_16 + #define FIL_RUNOUT2_PIN GPIO_PB16_J20_16 #endif // // LCD / Controller // #if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) - #define BEEPER_PIN 23 // D24 PA15_CTS1 - #define LCD_PINS_RS 17 // D17 PA12_RXD1 - #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 - #define LCD_PINS_D4 69 // D69 PA0_CANTX0 - #define LCD_PINS_D5 54 // D54 PA16_SCK1 - #define LCD_PINS_D6 68 // D68 PA1_CANRX0 - #define LCD_PINS_D7 34 // D34 PC2_PWML0 + #define BEEPER_PIN 23 // D24 PA15_CTS1 + #define LCD_PINS_RS 17 // D17 PA12_RXD1 + #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 + #define LCD_PINS_D4 69 // D69 PA0_CANTX0 + #define LCD_PINS_D5 54 // D54 PA16_SCK1 + #define LCD_PINS_D6 68 // D68 PA1_CANRX0 + #define LCD_PINS_D7 34 // D34 PC2_PWML0 - #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 + #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) // Buttons on AUX-2 - #define BTN_EN1 60 // D60 PA3_TIOB1 - #define BTN_EN2 13 // D13 PB27_TIOB0 - #define BTN_ENC 16 // D16 PA13_TXD1 // the click + #define BTN_EN1 60 // D60 PA3_TIOB1 + #define BTN_EN2 13 // D13 PB27_TIOB0 + #define BTN_ENC 16 // D16 PA13_TXD1 // the click #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index 69fb2a3dfc..f23d008bec 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -33,91 +33,91 @@ // // Servos // -#define SERVO0_PIN 6 +#define SERVO0_PIN 6 // // Limit Switches // -#define X_STOP_PIN 34 -#define Y_STOP_PIN 39 -#define Z_STOP_PIN 62 +#define X_STOP_PIN 34 +#define Y_STOP_PIN 39 +#define Z_STOP_PIN 62 #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 + #define Z_MIN_PROBE_PIN 49 #endif // // Steppers // -#define X_STEP_PIN 14 -#define X_DIR_PIN 25 -#define X_ENABLE_PIN 26 +#define X_STEP_PIN 14 +#define X_DIR_PIN 25 +#define X_ENABLE_PIN 26 -#define Y_STEP_PIN 11 -#define Y_DIR_PIN 12 -#define Y_ENABLE_PIN 15 +#define Y_STEP_PIN 11 +#define Y_DIR_PIN 12 +#define Y_ENABLE_PIN 15 -#define Z_STEP_PIN 24 -#define Z_DIR_PIN 27 -#define Z_ENABLE_PIN 28 +#define Z_STEP_PIN 24 +#define Z_DIR_PIN 27 +#define Z_ENABLE_PIN 28 -#define E0_STEP_PIN 64 -#define E0_DIR_PIN 65 -#define E0_ENABLE_PIN 63 +#define E0_STEP_PIN 64 +#define E0_DIR_PIN 65 +#define E0_ENABLE_PIN 63 -#define E1_STEP_PIN 8 -#define E1_DIR_PIN 7 -#define E1_ENABLE_PIN 29 +#define E1_STEP_PIN 8 +#define E1_DIR_PIN 7 +#define E1_ENABLE_PIN 29 // // Temperature Sensors // Analog Inputs // -#define TEMP_0_PIN 1 -#define TEMP_1_PIN 2 -#define TEMP_BED_PIN 4 +#define TEMP_0_PIN 1 +#define TEMP_1_PIN 2 +#define TEMP_BED_PIN 4 #ifndef TEMP_CHAMBER_PIN - #define TEMP_CHAMBER_PIN 5 + #define TEMP_CHAMBER_PIN 5 #endif // // Heaters // -#define HEATER_0_PIN 3 -#define HEATER_1_PIN 4 -#define HEATER_BED_PIN 32 -#define HEATER_CHAMBER_PIN 33 +#define HEATER_0_PIN 3 +#define HEATER_1_PIN 4 +#define HEATER_BED_PIN 32 +#define HEATER_CHAMBER_PIN 33 // // Fans // -//#define FAN0_PIN 8 -#define ORIG_E0_AUTO_FAN_PIN 30 -#define ORIG_E1_AUTO_FAN_PIN 30 -#define ORIG_E2_AUTO_FAN_PIN 30 -#define ORIG_E3_AUTO_FAN_PIN 30 -#define ORIG_CHAMBER_AUTO_FAN_PIN 10 +//#define FAN0_PIN 8 +#define ORIG_E0_AUTO_FAN_PIN 30 +#define ORIG_E1_AUTO_FAN_PIN 30 +#define ORIG_E2_AUTO_FAN_PIN 30 +#define ORIG_E3_AUTO_FAN_PIN 30 +#define ORIG_CHAMBER_AUTO_FAN_PIN 10 // // SD card // -#define SCK_PIN 76 -#define MISO_PIN 74 -#define MOSI_PIN 75 -#define SDSS 53 -#define SD_DETECT_PIN 40 +#define SCK_PIN 76 +#define MISO_PIN 74 +#define MOSI_PIN 75 +#define SDSS 53 +#define SD_DETECT_PIN 40 // Common I/O -//#define PWM_1_PIN 6 // probe -//#define PWM_2_PIN 13 -//#define SPARE_IO 17 -#define BEEPER_PIN 13 -#define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 31 +//#define PWM_1_PIN 6 // probe +//#define PWM_2_PIN 13 +//#define SPARE_IO 17 +#define BEEPER_PIN 13 +#define STAT_LED_BLUE_PIN -1 +#define STAT_LED_RED_PIN 31 // G425 CALIBRATION_GCODE default pin #ifndef CALIBRATION_PIN - #define CALIBRATION_PIN 66 + #define CALIBRATION_PIN 66 #endif diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index 4f352ff152..8f1fb75012 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -34,138 +34,138 @@ // // Servos // -#define SERVO0_PIN 5 -#define SERVO1_PIN 6 -#define SERVO2_PIN 13 -#define SERVO3_PIN -1 +#define SERVO0_PIN 5 +#define SERVO1_PIN 6 +#define SERVO2_PIN 13 +#define SERVO3_PIN -1 // // Limit Switches // -#define X_MIN_PIN 38 -#define X_MAX_PIN 36 -#define Y_MIN_PIN 34 -#define Y_MAX_PIN 32 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN 28 +#define X_MIN_PIN 38 +#define X_MAX_PIN 36 +#define Y_MIN_PIN 34 +#define Y_MAX_PIN 32 +#define Z_MIN_PIN 30 +#define Z_MAX_PIN 28 // // Steppers // -#define X_STEP_PIN 2 -#define X_DIR_PIN 3 -#define X_ENABLE_PIN 22 +#define X_STEP_PIN 2 +#define X_DIR_PIN 3 +#define X_ENABLE_PIN 22 -#define Y_STEP_PIN 17 -#define Y_DIR_PIN 16 -#define Y_ENABLE_PIN 26 +#define Y_STEP_PIN 17 +#define Y_DIR_PIN 16 +#define Y_ENABLE_PIN 26 -#define Z_STEP_PIN 61 // Z1 STP -#define Z_DIR_PIN 60 // Z1 DIR -#define Z_ENABLE_PIN 15 // Z1 ENA +#define Z_STEP_PIN 61 // Z1 STP +#define Z_DIR_PIN 60 // Z1 DIR +#define Z_ENABLE_PIN 15 // Z1 ENA -#define E0_STEP_PIN 64 // Z2 STP -#define E0_DIR_PIN 63 // Z2 DIR -#define E0_ENABLE_PIN 62 // Z2 ENA +#define E0_STEP_PIN 64 // Z2 STP +#define E0_DIR_PIN 63 // Z2 DIR +#define E0_ENABLE_PIN 62 // Z2 ENA -#define E1_STEP_PIN 51 // E1 STP -#define E1_DIR_PIN 53 // E1 DIR -#define E1_ENABLE_PIN 65 // E1 ENA +#define E1_STEP_PIN 51 // E1 STP +#define E1_DIR_PIN 53 // E1 DIR +#define E1_ENABLE_PIN 65 // E1 ENA -#define E2_STEP_PIN 24 // E2 STP -#define E2_DIR_PIN 23 // E2 DIR -#define E2_ENABLE_PIN 49 // E2 ENA +#define E2_STEP_PIN 24 // E2 STP +#define E2_DIR_PIN 23 // E2 DIR +#define E2_ENABLE_PIN 49 // E2 ENA // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input (HOTEND0 thermistor) -#define TEMP_1_PIN 2 // Analog Input (HOTEND1 thermistor) -#define TEMP_2_PIN 5 // Analog Input (unused) -#define TEMP_BED_PIN 1 // Analog Input (BED thermistor) +#define TEMP_0_PIN 0 // Analog Input (HOTEND0 thermistor) +#define TEMP_1_PIN 2 // Analog Input (HOTEND1 thermistor) +#define TEMP_2_PIN 5 // Analog Input (unused) +#define TEMP_BED_PIN 1 // Analog Input (BED thermistor) // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN -1 + #define MAX6675_SS_PIN -1 #else - #define MAX6675_SS_PIN -1 + #define MAX6675_SS_PIN -1 #endif // // Heaters / Fans // -#define HEATER_0_PIN 7 // HOTEND0 MOSFET -#define HEATER_1_PIN 8 // HOTEND1 MOSFET -#define HEATER_BED_PIN 39 // BED MOSFET +#define HEATER_0_PIN 7 // HOTEND0 MOSFET +#define HEATER_1_PIN 8 // HOTEND1 MOSFET +#define HEATER_BED_PIN 39 // BED MOSFET #ifndef FAN_PIN - #define FAN_PIN 11 // FAN1 header on board - PRINT FAN + #define FAN_PIN 11 // FAN1 header on board - PRINT FAN #endif -#define FAN1_PIN 9 // FAN2 header on board - CONTROLLER FAN -#define FAN2_PIN 12 // FAN3 header on board - EXTRUDER0 FAN +#define FAN1_PIN 9 // FAN2 header on board - CONTROLLER FAN +#define FAN2_PIN 12 // FAN3 header on board - EXTRUDER0 FAN // // Misc. Functions // -#define SDSS 4 -#define PS_ON_PIN 40 +#define SDSS 4 +#define PS_ON_PIN 40 // // LCD / Controller // #if HAS_SPI_LCD - #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 - #define LCD_PINS_D4 44 - #define LCD_PINS_D5 45 - #define LCD_PINS_D6 46 - #define LCD_PINS_D7 47 + #define LCD_PINS_RS 42 + #define LCD_PINS_ENABLE 43 + #define LCD_PINS_D4 44 + #define LCD_PINS_D5 45 + #define LCD_PINS_D6 46 + #define LCD_PINS_D7 47 #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 41 + #define BEEPER_PIN 41 - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 - #define SDSS 4 - #define SD_DETECT_PIN 14 + #define SDSS 4 + #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) - #define BEEPER_PIN 41 + #define BEEPER_PIN 41 - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 - #define BTN_BACK 71 + #define BTN_BACK 71 #undef SDSS - #define SDSS 4 - #define SD_DETECT_PIN 14 + #define SDSS 4 + #define SD_DETECT_PIN 14 #elif HAS_SSD1306_OLED_I2C - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 - #define BEEPER_PIN 41 - #define LCD_SDSS 4 - #define SD_DETECT_PIN 14 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 + #define BEEPER_PIN 41 + #define LCD_SDSS 4 + #define SD_DETECT_PIN 14 #elif ENABLED(SPARK_FULL_GRAPHICS) - #define LCD_PINS_D4 29 - #define LCD_PINS_ENABLE 27 - #define LCD_PINS_RS 25 + #define LCD_PINS_D4 29 + #define LCD_PINS_ENABLE 27 + #define LCD_PINS_RS 25 - #define BTN_EN1 35 - #define BTN_EN2 33 - #define BTN_ENC 37 + #define BTN_EN1 35 + #define BTN_EN2 33 + #define BTN_ENC 37 - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #endif // SPARK_FULL_GRAPHICS #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index 240204ced9..34706d5e90 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -34,141 +34,141 @@ // // Servos // -#define SERVO0_PIN 5 -#define SERVO1_PIN 6 -#define SERVO2_PIN 8 // 4-pin header FAN0 -#define SERVO3_PIN -1 +#define SERVO0_PIN 5 +#define SERVO1_PIN 6 +#define SERVO2_PIN 8 // 4-pin header FAN0 +#define SERVO3_PIN -1 // // Limit Switches // -#define X_MIN_PIN 38 -#define X_MAX_PIN -1 -#define Y_MIN_PIN 34 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN -1 +#define X_MIN_PIN 38 +#define X_MAX_PIN -1 +#define Y_MIN_PIN 34 +#define Y_MAX_PIN -1 +#define Z_MIN_PIN 30 +#define Z_MAX_PIN -1 // // Steppers // -#define X_STEP_PIN 17 -#define X_DIR_PIN 16 -#define X_ENABLE_PIN 22 +#define X_STEP_PIN 17 +#define X_DIR_PIN 16 +#define X_ENABLE_PIN 22 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 26 +#define Y_STEP_PIN 2 +#define Y_DIR_PIN 3 +#define Y_ENABLE_PIN 26 -#define Z_STEP_PIN 64 -#define Z_DIR_PIN 63 -#define Z_ENABLE_PIN 15 +#define Z_STEP_PIN 64 +#define Z_DIR_PIN 63 +#define Z_ENABLE_PIN 15 -#define E0_STEP_PIN 61 -#define E0_DIR_PIN 60 -#define E0_ENABLE_PIN 62 +#define E0_STEP_PIN 61 +#define E0_DIR_PIN 60 +#define E0_ENABLE_PIN 62 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input (HOTEND0 thermistor) -#define TEMP_1_PIN 2 // Analog Input (unused) -#define TEMP_2_PIN 5 // Analog Input (OnBoard thermistor beta 3950) -#define TEMP_BED_PIN 1 // Analog Input (BED thermistor) +#define TEMP_0_PIN 0 // Analog Input (HOTEND0 thermistor) +#define TEMP_1_PIN 2 // Analog Input (unused) +#define TEMP_2_PIN 5 // Analog Input (OnBoard thermistor beta 3950) +#define TEMP_BED_PIN 1 // Analog Input (BED thermistor) // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define MAX6675_SS_PIN 53 #else - #define MAX6675_SS_PIN 53 + #define MAX6675_SS_PIN 53 #endif // // Heaters / Fans // -#define HEATER_0_PIN 13 // HOTEND0 MOSFET -#define HEATER_BED_PIN 7 // BED MOSFET +#define HEATER_0_PIN 13 // HOTEND0 MOSFET +#define HEATER_BED_PIN 7 // BED MOSFET #ifndef FAN_PIN - #define FAN_PIN 11 // FAN1 header on board - PRINT FAN + #define FAN_PIN 11 // FAN1 header on board - PRINT FAN #endif -#define FAN1_PIN 12 // FAN2 header on board - CONTROLLER FAN -#define FAN2_PIN 9 // FAN3 header on board - EXTRUDER0 FAN -//#define FAN3_PIN 8 // FAN0 4-pin header on board +#define FAN1_PIN 12 // FAN2 header on board - CONTROLLER FAN +#define FAN2_PIN 9 // FAN3 header on board - EXTRUDER0 FAN +//#define FAN3_PIN 8 // FAN0 4-pin header on board // // Misc. Functions // -#define SDSS 4 -#define PS_ON_PIN 40 +#define SDSS 4 +#define PS_ON_PIN 40 // // LCD / Controller // #if HAS_SPI_LCD - #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 - #define LCD_PINS_D4 44 - #define LCD_PINS_D5 45 - #define LCD_PINS_D6 46 - #define LCD_PINS_D7 47 + #define LCD_PINS_RS 42 + #define LCD_PINS_ENABLE 43 + #define LCD_PINS_D4 44 + #define LCD_PINS_D5 45 + #define LCD_PINS_D6 46 + #define LCD_PINS_D7 47 #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 41 + #define BEEPER_PIN 41 - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 - #define SDSS 4 - #define SD_DETECT_PIN 14 + #define SDSS 4 + #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) - #define BEEPER_PIN 41 + #define BEEPER_PIN 41 - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 - #define BTN_BACK 71 + #define BTN_BACK 71 #undef SDSS - #define SDSS 4 - #define SD_DETECT_PIN 14 + #define SDSS 4 + #define SD_DETECT_PIN 14 #elif HAS_SSD1306_OLED_I2C - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 - #define BEEPER_PIN 41 - #define LCD_SDSS 4 - #define SD_DETECT_PIN 14 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 + #define BEEPER_PIN 41 + #define LCD_SDSS 4 + #define SD_DETECT_PIN 14 #elif ENABLED(SPARK_FULL_GRAPHICS) - #define LCD_PINS_D4 29 - #define LCD_PINS_ENABLE 27 - #define LCD_PINS_RS 25 + #define LCD_PINS_D4 29 + #define LCD_PINS_ENABLE 27 + #define LCD_PINS_RS 25 - #define BTN_EN1 35 - #define BTN_EN2 33 - #define BTN_ENC 37 + #define BTN_EN1 35 + #define BTN_EN2 33 + #define BTN_ENC 37 - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #elif ENABLED(MINIPANEL) - #define BTN_EN1 52 - #define BTN_EN2 50 - #define BTN_ENC 48 - #define LCD_SDSS 4 - #define SD_DETECT_PIN 14 - #define BEEPER_PIN 41 - #define DOGLCD_A0 46 - #define DOGLCD_CS 45 + #define BTN_EN1 52 + #define BTN_EN2 50 + #define BTN_ENC 48 + #define LCD_SDSS 4 + #define SD_DETECT_PIN 14 + #define BEEPER_PIN 41 + #define DOGLCD_A0 46 + #define DOGLCD_CS 45 #endif // SPARK_FULL_GRAPHICS #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h index c05c6169d6..b3a9e456a2 100644 --- a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h +++ b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h @@ -36,38 +36,38 @@ // // Servos // -//#define SERVO0_PIN -1 -//#define SERVO1_PIN -1 +//#define SERVO0_PIN -1 +//#define SERVO1_PIN -1 // // Limit Switches // -#define X_MIN_PIN 22 // PB26 -#define Y_MAX_PIN 18 // PA11 -#define Z_MIN_PIN 19 // PA10 +#define X_MIN_PIN 22 // PB26 +#define Y_MAX_PIN 18 // PA11 +#define Z_MIN_PIN 19 // PA10 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 22 + #define Z_MIN_PROBE_PIN 22 #endif #ifndef FIL_RUNOUT_PIN - //#define FIL_RUNOUT_PIN 57 // PA22 + //#define FIL_RUNOUT_PIN 57 // PA22 #endif #ifndef FIL_RUNOUT2_PIN - //#define FIL_RUNOUT2_PIN 21 // PB13 + //#define FIL_RUNOUT2_PIN 21 // PB13 #endif // // LED defines // -//#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) -//#define NEOPIXEL_PIN 20 // LED driving pin on motherboard -//#define NEOPIXEL_PIXELS 3 // Number of LEDs in the strip -//#define SDA0 20 // PB12 NeoPixel pin I2C data -//#define SCL0 21 // PB13 I2C clock +//#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) +//#define NEOPIXEL_PIN 20 // LED driving pin on motherboard +//#define NEOPIXEL_PIXELS 3 // Number of LEDs in the strip +//#define SDA0 20 // PB12 NeoPixel pin I2C data +//#define SCL0 21 // PB13 I2C clock // D0_12 #REF! (INDICATOR_LED) // B28 JTAG-CLK @@ -79,82 +79,82 @@ //A15 UART_CTS //PB2 Unassigned //PB4 to PB9 Unassigned -//#define UART_RX_PIN 0 // PA8 "RX0" -//#define UART_TX_PIN 1 // PA9 "TX0" -//#define UART_RTS_PIN 23 // PA14 -//#define UART_CTS_PIN 24 // PA15 +//#define UART_RX_PIN 0 // PA8 "RX0" +//#define UART_TX_PIN 1 // PA9 "TX0" +//#define UART_RTS_PIN 23 // PA14 +//#define UART_CTS_PIN 24 // PA15 // // Steppers // -#define Z_STEP_PIN 73 // PA21 MOTOR 1 -#define Z_DIR_PIN 75 // PA26 -#define Z_ENABLE_PIN 74 // PA25 +#define Z_STEP_PIN 73 // PA21 MOTOR 1 +#define Z_DIR_PIN 75 // PA26 +#define Z_ENABLE_PIN 74 // PA25 -#define X_STEP_PIN 66 // PB15 MOTOR 2 -#define X_DIR_PIN 54 // PA16 -#define X_ENABLE_PIN 67 // PB16 +#define X_STEP_PIN 66 // PB15 MOTOR 2 +#define X_DIR_PIN 54 // PA16 +#define X_ENABLE_PIN 67 // PB16 -#define Y_STEP_PIN 34 // PA29 MOTOR 3 -#define Y_DIR_PIN 35 // PB1 -#define Y_ENABLE_PIN 36 // PB0 +#define Y_STEP_PIN 34 // PA29 MOTOR 3 +#define Y_DIR_PIN 35 // PB1 +#define Y_ENABLE_PIN 36 // PB0 -#define E0_STEP_PIN 53 // PB14 MOTOR 4 -#define E0_DIR_PIN 78 // PB23 -#define E0_ENABLE_PIN 37 // PB22 +#define E0_STEP_PIN 53 // PB14 MOTOR 4 +#define E0_DIR_PIN 78 // PB23 +#define E0_ENABLE_PIN 37 // PB22 // Microstepping mode pins -#define Z_MS1_PIN 52 // PB21 MODE0 MOTOR 1 -#define Z_MS2_PIN 52 // PB21 MODE1 -#define Z_MS3_PIN 65 // PB20 MODE2 +#define Z_MS1_PIN 52 // PB21 MODE0 MOTOR 1 +#define Z_MS2_PIN 52 // PB21 MODE1 +#define Z_MS3_PIN 65 // PB20 MODE2 -#define X_MS1_PIN 43 // PA20 MODE0 MOTOR 2 -#define X_MS2_PIN 43 // PA20 MODE1 -#define X_MS3_PIN 42 // PA19 MODE2 +#define X_MS1_PIN 43 // PA20 MODE0 MOTOR 2 +#define X_MS2_PIN 43 // PA20 MODE1 +#define X_MS3_PIN 42 // PA19 MODE2 -#define Y_MS1_PIN 77 // PA28 MODE0 MOTOR 3 -#define Y_MS2_PIN 77 // PA28 MODE1 -#define Y_MS3_PIN 76 // PA27 MODE2 +#define Y_MS1_PIN 77 // PA28 MODE0 MOTOR 3 +#define Y_MS2_PIN 77 // PA28 MODE1 +#define Y_MS3_PIN 76 // PA27 MODE2 -#define E0_MS1_PIN 38 // PB11 MODE0 MOTOR 4 -#define E0_MS2_PIN 38 // PB11 MODE1 -#define E0_MS3_PIN 39 // PB10 MODE2 +#define E0_MS1_PIN 38 // PB11 MODE0 MOTOR 4 +#define E0_MS2_PIN 38 // PB11 MODE1 +#define E0_MS3_PIN 39 // PB10 MODE2 // Motor current PWM pins -#define MOTOR_CURRENT_PWM_X_PIN 62 // PB17 MOTOR 1 -#define MOTOR_CURRENT_PWM_Z_PIN 63 // PB18 MOTOR 2 -#define MOTOR_CURRENT_PWM_Y_PIN 64 // PB19 MOTOR 3 -#define MOTOR_CURRENT_PWM_E_PIN 61 // PA2 MOTOR 4 +#define MOTOR_CURRENT_PWM_X_PIN 62 // PB17 MOTOR 1 +#define MOTOR_CURRENT_PWM_Z_PIN 63 // PB18 MOTOR 2 +#define MOTOR_CURRENT_PWM_Y_PIN 64 // PB19 MOTOR 3 +#define MOTOR_CURRENT_PWM_E_PIN 61 // PA2 MOTOR 4 #define DEFAULT_PWM_MOTOR_CURRENT { 300, 400, 1000} // XY Z E0, 1000 = 1000mAh // // Temperature Sensors // -#define TEMP_0_PIN 2 // digital 56 PA23 -#define TEMP_BED_PIN 5 // digital 59 PA4 +#define TEMP_0_PIN 2 // digital 56 PA23 +#define TEMP_BED_PIN 5 // digital 59 PA4 // // Heaters / Fans // -#define HEATER_0_PIN 40 // PA5 -#define HEATER_BED_PIN 41 // PB24 +#define HEATER_0_PIN 40 // PA5 +#define HEATER_BED_PIN 41 // PB24 #ifndef FAN_PIN - #define FAN_PIN 13 // PB27 Fan1A + #define FAN_PIN 13 // PB27 Fan1A #endif -#define FAN1_PIN 58 // PA6 Fan1B +#define FAN1_PIN 58 // PA6 Fan1B -#define FET_SAFETY_PIN 31 // PA7 must be pulsed low every 50 mS or FETs are turned off -#define FET_SAFETY_DELAY 50 // 50 mS delay between pulses -#define FET_SAFETY_INVERTED true // true - negative going pulse of 2 uS +#define FET_SAFETY_PIN 31 // PA7 must be pulsed low every 50 mS or FETs are turned off +#define FET_SAFETY_DELAY 50 // 50 mS delay between pulses +#define FET_SAFETY_INVERTED true // true - negative going pulse of 2 uS ///////////////////////////////////////////////////////// -#define MISO_PIN 68 // set to unused pins for now -#define MOSI_PIN 69 // set to unused pins for now -#define SCK_PIN 70 // set to unused pins for now -#define SDSS 71 // set to unused pins for now +#define MISO_PIN 68 // set to unused pins for now +#define MOSI_PIN 69 // set to unused pins for now +#define SCK_PIN 70 // set to unused pins for now +#define SDSS 71 // set to unused pins for now /** * G2 uses 8 pins that are not available in the DUE environment: diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index 41daba4e8e..3bc52e9387 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -35,187 +35,187 @@ // Servos // #if !HAS_CUTTER - #define SERVO0_PIN 5 + #define SERVO0_PIN 5 #endif -#define SERVO1_PIN 6 -#define SERVO2_PIN 39 -#define SERVO3_PIN 40 +#define SERVO1_PIN 6 +#define SERVO2_PIN 39 +#define SERVO3_PIN 40 // // Limit Switches // -#define X_MIN_PIN 28 -#define X_MAX_PIN 34 -#define Y_MIN_PIN 30 -#define Y_MAX_PIN 36 -#define Z_MIN_PIN 32 -#define Z_MAX_PIN 38 +#define X_MIN_PIN 28 +#define X_MAX_PIN 34 +#define Y_MIN_PIN 30 +#define Y_MAX_PIN 36 +#define Z_MIN_PIN 32 +#define Z_MAX_PIN 38 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 38 + #define Z_MIN_PROBE_PIN 38 #endif // // Steppers // -#define X_STEP_PIN 24 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 26 +#define X_STEP_PIN 24 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 26 #ifndef X_CS_PIN - #define X_CS_PIN 25 + #define X_CS_PIN 25 #endif -#define Y_STEP_PIN 17 -#define Y_DIR_PIN 16 -#define Y_ENABLE_PIN 22 +#define Y_STEP_PIN 17 +#define Y_DIR_PIN 16 +#define Y_ENABLE_PIN 22 #ifndef Y_CS_PIN - #define Y_CS_PIN 27 + #define Y_CS_PIN 27 #endif -#define Z_STEP_PIN 2 -#define Z_DIR_PIN 3 -#define Z_ENABLE_PIN 15 +#define Z_STEP_PIN 2 +#define Z_DIR_PIN 3 +#define Z_ENABLE_PIN 15 #ifndef Z_CS_PIN - #define Z_CS_PIN 29 + #define Z_CS_PIN 29 #endif -#define E0_STEP_PIN 61 -#define E0_DIR_PIN 60 -#define E0_ENABLE_PIN 62 +#define E0_STEP_PIN 61 +#define E0_DIR_PIN 60 +#define E0_ENABLE_PIN 62 #ifndef E0_CS_PIN - #define E0_CS_PIN 31 + #define E0_CS_PIN 31 #endif -#define E1_STEP_PIN 64 -#define E1_DIR_PIN 63 -#define E1_ENABLE_PIN 65 +#define E1_STEP_PIN 64 +#define E1_DIR_PIN 63 +#define E1_ENABLE_PIN 65 #ifndef E1_CS_PIN - #define E1_CS_PIN 33 + #define E1_CS_PIN 33 #endif -#define E2_STEP_PIN 51 -#define E2_DIR_PIN 53 -#define E2_ENABLE_PIN 49 +#define E2_STEP_PIN 51 +#define E2_DIR_PIN 53 +#define E2_ENABLE_PIN 49 #ifndef E2_CS_PIN - #define E2_CS_PIN 35 + #define E2_CS_PIN 35 #endif /** * RADDS Extension Board V2 / V3 * http://doku.radds.org/dokumentation/extension-board */ -//#define RADDS_EXTENSION 2 +//#define RADDS_EXTENSION 2 #if RADDS_EXTENSION >= 2 - #define E3_DIR_PIN 33 - #define E3_STEP_PIN 35 - #define E3_ENABLE_PIN 37 + #define E3_DIR_PIN 33 + #define E3_STEP_PIN 35 + #define E3_ENABLE_PIN 37 #ifndef E3_CS_PIN - #define E3_CS_PIN 6 + #define E3_CS_PIN 6 #endif #if RADDS_EXTENSION == 3 - #define E4_DIR_PIN 27 - #define E4_STEP_PIN 29 - #define E4_ENABLE_PIN 31 + #define E4_DIR_PIN 27 + #define E4_STEP_PIN 29 + #define E4_ENABLE_PIN 31 #ifndef E4_CS_PIN - #define E4_CS_PIN 39 + #define E4_CS_PIN 39 #endif - #define E5_DIR_PIN 66 - #define E5_STEP_PIN 67 - #define E5_ENABLE_PIN 68 + #define E5_DIR_PIN 66 + #define E5_STEP_PIN 67 + #define E5_ENABLE_PIN 68 #ifndef E5_CS_PIN - #define E5_CS_PIN 6 + #define E5_CS_PIN 6 #endif - #define RADDS_EXT_MSI_PIN 69 + #define RADDS_EXT_MSI_PIN 69 #define BOARD_INIT() OUT_WRITE(RADDS_EXT_VDD_PIN, HIGH) #else - #define E4_DIR_PIN 27 - #define E4_STEP_PIN 29 - #define E4_ENABLE_PIN 31 + #define E4_DIR_PIN 27 + #define E4_STEP_PIN 29 + #define E4_ENABLE_PIN 31 #ifndef E4_CS_PIN - #define E4_CS_PIN 39 + #define E4_CS_PIN 39 #endif // E3 and E4 share the same MSx pins - #define E3_MS1_PIN 67 - #define E4_MS1_PIN 67 - #define E3_MS2_PIN 68 - #define E4_MS2_PIN 68 - #define E3_MS3_PIN 69 - #define E4_MS3_PIN 69 + #define E3_MS1_PIN 67 + #define E4_MS1_PIN 67 + #define E3_MS2_PIN 68 + #define E4_MS2_PIN 68 + #define E3_MS3_PIN 69 + #define E4_MS3_PIN 69 - #define RADDS_EXT_VDD2_PIN 66 + #define RADDS_EXT_VDD2_PIN 66 #define BOARD_INIT() do{ OUT_WRITE(RADDS_EXT_VDD_PIN, HIGH); OUT_WRITE(RADDS_EXT_VDD2_PIN, HIGH); }while(0) #endif - #define RADDS_EXT_VDD_PIN 25 + #define RADDS_EXT_VDD_PIN 25 #endif // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_2_PIN 2 // Analog Input -#define TEMP_3_PIN 3 // Analog Input -#define TEMP_4_PIN 5 // dummy so will compile when PINS_DEBUGGING is enabled -#define TEMP_BED_PIN 4 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_2_PIN 2 // Analog Input +#define TEMP_3_PIN 3 // Analog Input +#define TEMP_4_PIN 5 // dummy so will compile when PINS_DEBUGGING is enabled +#define TEMP_BED_PIN 4 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define MAX6675_SS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define MAX6675_SS_PIN 49 #endif // // Heaters / Fans // -#define HEATER_0_PIN 13 -#define HEATER_1_PIN 12 -#define HEATER_2_PIN 11 +#define HEATER_0_PIN 13 +#define HEATER_1_PIN 12 +#define HEATER_2_PIN 11 #if !HAS_CUTTER - #define HEATER_BED_PIN 7 // BED + #define HEATER_BED_PIN 7 // BED #endif #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN 9 #endif -#define FAN1_PIN 8 +#define FAN1_PIN 8 // // Misc. Functions // -#define SD_DETECT_PIN 14 -#define PS_ON_PIN 40 // SERVO3_PIN +#define SD_DETECT_PIN 14 +#define PS_ON_PIN 40 // SERVO3_PIN #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 39 // SERVO2_PIN + #define FIL_RUNOUT_PIN 39 // SERVO2_PIN #endif #define I2C_EEPROM -#define E2END 0x1FFF // 8KB +#define E2END 0x1FFF // 8KB // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER #if !NUM_SERVOS - #define SPINDLE_LASER_PWM_PIN 5 // SERVO0_PIN + #define SPINDLE_LASER_PWM_PIN 5 // SERVO0_PIN #endif - #define SPINDLE_LASER_ENA_PIN 7 // HEATER_BED_PIN - Pullup/down! + #define SPINDLE_LASER_ENA_PIN 7 // HEATER_BED_PIN - Pullup/down! #endif // @@ -225,65 +225,65 @@ #if ENABLED(RADDS_DISPLAY) - #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 - #define LCD_PINS_D4 44 - #define LCD_PINS_D5 45 - #define LCD_PINS_D6 46 - #define LCD_PINS_D7 47 + #define LCD_PINS_RS 42 + #define LCD_PINS_ENABLE 43 + #define LCD_PINS_D4 44 + #define LCD_PINS_D5 45 + #define LCD_PINS_D6 46 + #define LCD_PINS_D7 47 - #define BEEPER_PIN 41 + #define BEEPER_PIN 41 - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 - #define BTN_BACK 71 + #define BTN_BACK 71 - #define SDSS 10 - #define SD_DETECT_PIN 14 + #define SDSS 10 + #define SD_DETECT_PIN 14 #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) // The REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER requires // an adapter such as https://www.thingiverse.com/thing:1740725 - #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 - #define LCD_PINS_D4 44 + #define LCD_PINS_RS 42 + #define LCD_PINS_ENABLE 43 + #define LCD_PINS_D4 44 - #define BEEPER_PIN 41 + #define BEEPER_PIN 41 - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 - #define SDSS 10 - #define SD_DETECT_PIN 14 + #define SDSS 10 + #define SD_DETECT_PIN 14 #elif HAS_SSD1306_OLED_I2C - #define BTN_EN1 50 - #define BTN_EN2 52 - #define BTN_ENC 48 - #define BEEPER_PIN 41 - #define LCD_SDSS 10 - #define SD_DETECT_PIN 14 + #define BTN_EN1 50 + #define BTN_EN2 52 + #define BTN_ENC 48 + #define BEEPER_PIN 41 + #define LCD_SDSS 10 + #define SD_DETECT_PIN 14 #elif ENABLED(SPARK_FULL_GRAPHICS) - #define LCD_PINS_D4 29 - #define LCD_PINS_ENABLE 27 - #define LCD_PINS_RS 25 + #define LCD_PINS_D4 29 + #define LCD_PINS_ENABLE 27 + #define LCD_PINS_RS 25 - #define BTN_EN1 35 - #define BTN_EN2 33 - #define BTN_ENC 37 + #define BTN_EN1 35 + #define BTN_EN2 33 + #define BTN_ENC 37 #endif // SPARK_FULL_GRAPHICS #endif // HAS_SPI_LCD #ifndef SDSS - #define SDSS 4 + #define SDSS 4 #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index d25ef9e059..916dbf6430 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -56,20 +56,20 @@ // Temperature Sensors // #undef TEMP_0_PIN -#define TEMP_0_PIN 9 // Analog Input +#define TEMP_0_PIN 9 // Analog Input #undef TEMP_1_PIN -#define TEMP_1_PIN 11 // Analog Input +#define TEMP_1_PIN 11 // Analog Input #undef TEMP_BED_PIN -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #undef MAX6675_SS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 69 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 69 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 69 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 69 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -79,13 +79,13 @@ #if BOTH(NEWPANEL, PANEL_ONE) #undef LCD_PINS_D4 - #define LCD_PINS_D4 68 + #define LCD_PINS_D4 68 #undef LCD_PINS_D5 - #define LCD_PINS_D5 69 + #define LCD_PINS_D5 69 #undef LCD_PINS_D7 - #define LCD_PINS_D7 67 + #define LCD_PINS_D7 67 #endif #if ENABLED(NEWPANEL) @@ -93,36 +93,36 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #undef BTN_EN1 - #define BTN_EN1 67 + #define BTN_EN1 67 #undef BTN_ENC - #define BTN_ENC 66 + #define BTN_ENC 66 #elif ENABLED(MINIPANEL) #undef DOGLCD_CS - #define DOGLCD_CS 69 + #define DOGLCD_CS 69 #undef LCD_BACKLIGHT_PIN - #define LCD_BACKLIGHT_PIN 68 // backlight LED on A14/D68 + #define LCD_BACKLIGHT_PIN 68 // backlight LED on A14/D68 #undef KILL_PIN - #define KILL_PIN 67 + #define KILL_PIN 67 #undef BTN_EN2 - #define BTN_EN2 66 + #define BTN_EN2 66 #else #if ENABLED(REPRAPWORLD_KEYPAD) #undef BTN_EN1 - #define BTN_EN1 67 // encoder + #define BTN_EN1 67 // encoder #undef BTN_ENC - #define BTN_ENC 66 // enter button + #define BTN_ENC 66 // enter button #elif ENABLED(PANEL_ONE) #undef BTN_EN2 - #define BTN_EN2 66 // AUX2 PIN 4 + #define BTN_EN2 66 // AUX2 PIN 4 #endif #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index ee44dd7950..297aaa9cb8 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -43,98 +43,98 @@ // // Servos // -#define SERVO0_PIN 7 -#define SERVO1_PIN 6 -#define SERVO2_PIN 5 -#define SERVO3_PIN 3 +#define SERVO0_PIN 7 +#define SERVO1_PIN 6 +#define SERVO2_PIN 5 +#define SERVO3_PIN 3 // // Limit Switches // -#define X_MIN_PIN 22 -#define X_MAX_PIN 30 -#define Y_MIN_PIN 24 -#define Y_MAX_PIN 38 -#define Z_MIN_PIN 26 -#define Z_MAX_PIN 34 +#define X_MIN_PIN 22 +#define X_MAX_PIN 30 +#define Y_MIN_PIN 24 +#define Y_MAX_PIN 38 +#define Z_MIN_PIN 26 +#define Z_MAX_PIN 34 // // Steppers // -#define X_STEP_PIN 63 -#define X_DIR_PIN 62 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN 63 +#define X_DIR_PIN 62 +#define X_ENABLE_PIN 48 #ifndef X_CS_PIN - #define X_CS_PIN 68 + #define X_CS_PIN 68 #endif -#define Y_STEP_PIN 65 -#define Y_DIR_PIN 64 -#define Y_ENABLE_PIN 46 +#define Y_STEP_PIN 65 +#define Y_DIR_PIN 64 +#define Y_ENABLE_PIN 46 #ifndef Y_CS_PIN - #define Y_CS_PIN 60 + #define Y_CS_PIN 60 #endif -#define Z_STEP_PIN 67 -#define Z_DIR_PIN 66 -#define Z_ENABLE_PIN 44 +#define Z_STEP_PIN 67 +#define Z_DIR_PIN 66 +#define Z_ENABLE_PIN 44 #ifndef Z_CS_PIN - #define Z_CS_PIN 58 + #define Z_CS_PIN 58 #endif -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 42 +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 42 #ifndef E0_CS_PIN - #define E0_CS_PIN 67 + #define E0_CS_PIN 67 #endif -#define E1_STEP_PIN 43 -#define E1_DIR_PIN 41 -#define E1_ENABLE_PIN 39 +#define E1_STEP_PIN 43 +#define E1_DIR_PIN 41 +#define E1_ENABLE_PIN 39 #ifndef E1_CS_PIN - #define E1_CS_PIN 61 + #define E1_CS_PIN 61 #endif -#define E2_STEP_PIN 32 -#define E2_DIR_PIN 47 -#define E2_ENABLE_PIN 45 +#define E2_STEP_PIN 32 +#define E2_DIR_PIN 47 +#define E2_ENABLE_PIN 45 #ifndef E2_CS_PIN - #define E2_CS_PIN 59 + #define E2_CS_PIN 59 #endif // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_1_PIN 2 // Analog Input -#define TEMP_2_PIN 3 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_1_PIN 2 // Analog Input +#define TEMP_2_PIN 3 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define MAX6675_SS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define MAX6675_SS_PIN 49 #endif // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 10 -#define HEATER_2_PIN 11 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 10 +#define HEATER_2_PIN 11 +#define HEATER_BED_PIN 8 #ifndef FAN_PIN - #define FAN_PIN 12 + #define FAN_PIN 12 #endif // // Misc. Functions // -#define SDSS 4 -#define LED_PIN 13 +#define SDSS 4 +#define LED_PIN 13 // // LCD / Controller @@ -142,65 +142,65 @@ #if HAS_SPI_LCD // ramps-fd lcd adaptor - #define BEEPER_PIN 37 - #define BTN_EN1 33 - #define BTN_EN2 31 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define BEEPER_PIN 37 + #define BTN_EN1 33 + #define BTN_EN2 31 + #define BTN_ENC 35 + #define SD_DETECT_PIN 49 #if ENABLED(NEWPANEL) - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 #endif #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS LCD_PINS_ENABLE - #define DOGLCD_A0 LCD_PINS_RS - #define DOGLCD_SCK 76 - #define DOGLCD_MOSI 75 + #define DOGLCD_CS LCD_PINS_ENABLE + #define DOGLCD_A0 LCD_PINS_RS + #define DOGLCD_SCK 76 + #define DOGLCD_MOSI 75 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN 25 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN 27 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN 29 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN 25 #endif #elif ENABLED(NEWPANEL) - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #if ENABLED(MINIPANEL) - #define DOGLCD_CS 25 - #define DOGLCD_A0 27 + #define DOGLCD_CS 25 + #define DOGLCD_A0 27 #endif #endif #if ANY(VIKI2, miniVIKI) - #define DOGLCD_A0 16 - #define KILL_PIN 51 - #define STAT_LED_BLUE_PIN 29 - #define STAT_LED_RED_PIN 23 - #define DOGLCD_CS 17 - #define DOGLCD_SCK 76 // SCK_PIN - Required for DUE Hardware SPI - #define DOGLCD_MOSI 75 // MOSI_PIN - #define DOGLCD_MISO 74 // MISO_PIN + #define DOGLCD_A0 16 + #define KILL_PIN 51 + #define STAT_LED_BLUE_PIN 29 + #define STAT_LED_RED_PIN 23 + #define DOGLCD_CS 17 + #define DOGLCD_SCK 76 // SCK_PIN - Required for DUE Hardware SPI + #define DOGLCD_MOSI 75 // MOSI_PIN + #define DOGLCD_MISO 74 // MISO_PIN #endif #endif // HAS_SPI_LCD @@ -229,7 +229,7 @@ // M3/M4/M5 - Spindle/Laser Control // #if HOTENDS < 3 && HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) - #define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA - #define SPINDLE_LASER_PWM_PIN 12 // Hardware PWM - #define SPINDLE_DIR_PIN 47 // Use E2 DIR + #define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA + #define SPINDLE_LASER_PWM_PIN 12 // Hardware PWM + #define SPINDLE_DIR_PIN 47 // Use E2 DIR #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 455d40a999..0fd4a6b3ea 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -73,26 +73,26 @@ #define I2C_EEPROM #define E2END 0xFFF -#define RESET_PIN 42 // Resets the board if the jumper is attached +#define RESET_PIN 42 // Resets the board if the jumper is attached // // Temperature Sensors // #undef TEMP_0_PIN -#define TEMP_0_PIN 9 // Analog Input +#define TEMP_0_PIN 9 // Analog Input #undef TEMP_1_PIN -#define TEMP_1_PIN 10 // Analog Input +#define TEMP_1_PIN 10 // Analog Input #undef TEMP_BED_PIN -#define TEMP_BED_PIN 11 // Analog Input +#define TEMP_BED_PIN 11 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #undef MAX6675_SS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 67 // Don't use 53 if using Display/SD card + #define MAX6675_SS_PIN 67 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 67 // Don't use 49 (SD_DETECT_PIN) + #define MAX6675_SS_PIN 67 // Don't use 49 (SD_DETECT_PIN) #endif // @@ -100,12 +100,12 @@ // // Support for AZSMZ 12864 LCD with SD Card 3D printer smart controller control panel #if ENABLED(AZSMZ_12864) - #define BEEPER_PIN 66 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 65 - #define DOGLCD_A0 59 - #define DOGLCD_CS 44 - #define BTN_EN1 58 - #define BTN_EN2 40 - #define BTN_ENC 67 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 66 - #define SD_DETECT_PIN 49 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 42 + #define BEEPER_PIN 66 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 65 + #define DOGLCD_A0 59 + #define DOGLCD_CS 44 + #define BTN_EN1 58 + #define BTN_EN2 40 + #define BTN_ENC 67 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 66 + #define SD_DETECT_PIN 49 // Pin 49 for display sd interface, 72 for easy adapter board + #define KILL_PIN 42 #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 6963a164bb..7b844b5be0 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -41,76 +41,76 @@ // // Servos // -#define SERVO0_PIN 5 -#define SERVO1_PIN 3 +#define SERVO0_PIN 5 +#define SERVO1_PIN 3 // // Limit Switches // -#define X_MIN_PIN 45 -#define X_MAX_PIN 39 -#define Y_MIN_PIN 46 -#define Y_MAX_PIN 41 -#define Z_MIN_PIN 47 -#define Z_MAX_PIN 43 +#define X_MIN_PIN 45 +#define X_MAX_PIN 39 +#define Y_MIN_PIN 46 +#define Y_MAX_PIN 41 +#define Z_MIN_PIN 47 +#define Z_MAX_PIN 43 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 43 + #define Z_MIN_PROBE_PIN 43 #endif // // Steppers // -#define X_STEP_PIN 37 // Support Extension Board -#define X_DIR_PIN 36 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 37 // Support Extension Board +#define X_DIR_PIN 36 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN -1 + #define X_CS_PIN -1 #endif -#define Y_STEP_PIN 32 // Support Extension Board -#define Y_DIR_PIN 35 -#define Y_ENABLE_PIN 34 +#define Y_STEP_PIN 32 // Support Extension Board +#define Y_DIR_PIN 35 +#define Y_ENABLE_PIN 34 #ifndef Y_CS_PIN - #define Y_CS_PIN -1 + #define Y_CS_PIN -1 #endif -#define Z_STEP_PIN 30 // Support Extension Board -#define Z_DIR_PIN 2 -#define Z_ENABLE_PIN 33 +#define Z_STEP_PIN 30 // Support Extension Board +#define Z_DIR_PIN 2 +#define Z_ENABLE_PIN 33 #ifndef Z_CS_PIN - #define Z_CS_PIN -1 + #define Z_CS_PIN -1 #endif -#define E0_STEP_PIN 29 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 31 +#define E0_STEP_PIN 29 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 31 #ifndef E0_CS_PIN - #define E0_CS_PIN -1 + #define E0_CS_PIN -1 #endif -#define E1_STEP_PIN 22 -#define E1_DIR_PIN 24 -#define E1_ENABLE_PIN 26 +#define E1_STEP_PIN 22 +#define E1_DIR_PIN 24 +#define E1_ENABLE_PIN 26 #ifndef E1_CS_PIN - #define E1_CS_PIN -1 + #define E1_CS_PIN -1 #endif -#define E2_STEP_PIN 25 -#define E2_DIR_PIN 23 -#define E2_ENABLE_PIN 27 +#define E2_STEP_PIN 25 +#define E2_DIR_PIN 23 +#define E2_ENABLE_PIN 27 #ifndef E2_CS_PIN - #define E2_CS_PIN -1 + #define E2_CS_PIN -1 #endif -#define E3_STEP_PIN 15 // Only For Extension Board -#define E3_DIR_PIN 14 -#define E3_ENABLE_PIN 61 +#define E3_STEP_PIN 15 // Only For Extension Board +#define E3_DIR_PIN 14 +#define E3_ENABLE_PIN 61 #ifndef E3_CS_PIN - #define E3_CS_PIN -1 + #define E3_CS_PIN -1 #endif // For Future: Microstepping pins - Mapping not from fastio.h (?) @@ -119,77 +119,77 @@ //#define E3_MS3_PIN ? #if HAS_CUSTOM_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 + #define Z_MIN_PROBE_PIN 49 #endif #if HAS_FILAMENT_SENSOR #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN Y_MIN_PIN + #define FIL_RUNOUT_PIN Y_MIN_PIN #endif #endif // // Heaters / Fans // -#define HEATER_0_PIN 13 -#define HEATER_1_PIN 12 -#define HEATER_2_PIN 11 -#define HEATER_BED_PIN 7 // BED H1 +#define HEATER_0_PIN 13 +#define HEATER_1_PIN 12 +#define HEATER_2_PIN 11 +#define HEATER_BED_PIN 7 // BED H1 #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN 9 #endif -#define FAN1_PIN 8 -#define CONTROLLER_FAN_PIN -1 +#define FAN1_PIN 8 +#define CONTROLLER_FAN_PIN -1 // // Temperature Sensors // -#define TEMP_0_PIN 0 // ANALOG A0 -#define TEMP_1_PIN 1 // ANALOG A1 -#define TEMP_2_PIN 2 // ANALOG A2 -#define TEMP_3_PIN 3 // ANALOG A3 -#define TEMP_BED_PIN 4 // ANALOG A4 +#define TEMP_0_PIN 0 // ANALOG A0 +#define TEMP_1_PIN 1 // ANALOG A1 +#define TEMP_2_PIN 2 // ANALOG A2 +#define TEMP_3_PIN 3 // ANALOG A3 +#define TEMP_BED_PIN 4 // ANALOG A4 // The thermocouple uses Analog pins -#if ENABLED(VER_WITH_THERMOCOUPLE) // Defined in Configuration.h - #define TEMP_4_PIN 5 // A5 - #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) +#if ENABLED(VER_WITH_THERMOCOUPLE) // Defined in Configuration.h + #define TEMP_4_PIN 5 // A5 + #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) #endif // SPI for Max6675 or Max31855 Thermocouple /* #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define MAX6675_SS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define MAX6675_SS_PIN 49 #endif */ // // Misc. Functions // -#define SDSS 4 // 4,10,52 if using HW SPI. -#define LED_PIN -1 // 13 - HEATER_0_PIN -#define PS_ON_PIN -1 // 65 +#define SDSS 4 // 4,10,52 if using HW SPI. +#define LED_PIN -1 // 13 - HEATER_0_PIN +#define PS_ON_PIN -1 // 65 // MKS TFT / Nextion Use internal USART-1 -#define TFT_LCD_MODULE_COM 1 -#define TFT_LCD_MODULE_BAUDRATE 115600 +#define TFT_LCD_MODULE_COM 1 +#define TFT_LCD_MODULE_BAUDRATE 115600 // ESP WiFi Use internal USART-2 -#define ESP_WIFI_MODULE_COM 2 -#define ESP_WIFI_MODULE_BAUDRATE 115600 -#define ESP_WIFI_MODULE_RESET_PIN -1 -#define PIGGY_GPIO_PIN -1 +#define ESP_WIFI_MODULE_COM 2 +#define ESP_WIFI_MODULE_BAUDRATE 115600 +#define ESP_WIFI_MODULE_RESET_PIN -1 +#define PIGGY_GPIO_PIN -1 // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) -#define I2C_EEPROM // EEPROM on I2C-0 -//#define EEPROM_SD // EEPROM on SDCARD -//#define SPI_EEPROM // EEPROM on SPI-0 +#define E2END 0x7FFF // 32Kb (24lc256) +#define I2C_EEPROM // EEPROM on I2C-0 +//#define EEPROM_SD // EEPROM on SDCARD +//#define SPI_EEPROM // EEPROM on SPI-0 //#define SPI_CHAN_EEPROM1 ? //#define SPI_EEPROM1_CS ? // 2K EEPROM @@ -203,72 +203,72 @@ #if HAS_SPI_LCD #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BEEPER_PIN 62 - #define LCD_PINS_D4 48 - #define LCD_PINS_D5 50 - #define LCD_PINS_D6 52 - #define LCD_PINS_D7 53 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN 62 + #define LCD_PINS_D4 48 + #define LCD_PINS_D5 50 + #define LCD_PINS_D6 52 + #define LCD_PINS_D7 53 + #define SD_DETECT_PIN 51 #endif #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER) - #define LCD_PINS_RS 63 - #define LCD_PINS_ENABLE 64 + #define LCD_PINS_RS 63 + #define LCD_PINS_ENABLE 64 #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS 52 - #define LCD_PINS_ENABLE 53 + #define LCD_PINS_RS 52 + #define LCD_PINS_ENABLE 53 #elif HAS_SSD1306_OLED_I2C - #define BEEPER_PIN 62 - #define LCD_SDSS 10 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN 62 + #define LCD_SDSS 10 + #define SD_DETECT_PIN 51 #elif ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN 62 - #define DOGLCD_CS 64 - #define DOGLCD_A0 63 + #define BEEPER_PIN 62 + #define DOGLCD_CS 64 + #define DOGLCD_A0 63 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 48 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN 48 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 50 // D5 + #define RGB_LED_R_PIN 50 // D5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 52 // D6 + #define RGB_LED_G_PIN 52 // D6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 53 // D7 + #define RGB_LED_B_PIN 53 // D7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 50 // D5 + #define NEOPIXEL_PIN 50 // D5 #endif #elif ENABLED(SPARK_FULL_GRAPHICS) //http://doku.radds.org/dokumentation/other-electronics/sparklcd/ #error "Oops! SPARK_FULL_GRAPHICS not supported with RURAMPS4D." - //#define LCD_PINS_D4 29 //? - //#define LCD_PINS_ENABLE 27 //? - //#define LCD_PINS_RS 25 //? - //#define BTN_EN1 35 //? - //#define BTN_EN2 33 //? - //#define BTN_ENC 37 //? + //#define LCD_PINS_D4 29 //? + //#define LCD_PINS_ENABLE 27 //? + //#define LCD_PINS_RS 25 //? + //#define BTN_EN1 35 //? + //#define BTN_EN2 33 //? + //#define BTN_ENC 37 //? #endif // SPARK_FULL_GRAPHICS #if ENABLED(NEWPANEL) - #define BTN_EN1 44 - #define BTN_EN2 42 - #define BTN_ENC 40 + #define BTN_EN1 44 + #define BTN_EN2 42 + #define BTN_ENC 40 #endif #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index d0c24e68a3..3ba6fd17cf 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -41,141 +41,141 @@ // // Servos // -#define SERVO0_PIN 5 -#define SERVO1_PIN 3 +#define SERVO0_PIN 5 +#define SERVO1_PIN 3 // // Limit Switches // -#define X_MIN_PIN 45 -#define X_MAX_PIN 39 -#define Y_MIN_PIN 46 -#define Y_MAX_PIN 41 -#define Z_MIN_PIN 47 -#define Z_MAX_PIN 43 +#define X_MIN_PIN 45 +#define X_MAX_PIN 39 +#define Y_MIN_PIN 46 +#define Y_MAX_PIN 41 +#define Z_MIN_PIN 47 +#define Z_MAX_PIN 43 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 + #define Z_MIN_PROBE_PIN 49 #endif // // Steppers // -#define X_STEP_PIN 37 // Support Extension Board -#define X_DIR_PIN 36 -#define X_ENABLE_PIN 31 +#define X_STEP_PIN 37 // Support Extension Board +#define X_DIR_PIN 36 +#define X_ENABLE_PIN 31 #ifndef X_CS_PIN - #define X_CS_PIN 38 + #define X_CS_PIN 38 #endif -#define Y_STEP_PIN 32 // Support Extension Board -#define Y_DIR_PIN 35 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN 32 // Support Extension Board +#define Y_DIR_PIN 35 +#define Y_ENABLE_PIN 31 #ifndef Y_CS_PIN - #define Y_CS_PIN 34 + #define Y_CS_PIN 34 #endif -#define Z_STEP_PIN 30 // Support Extension Board -#define Z_DIR_PIN 2 -#define Z_ENABLE_PIN 31 +#define Z_STEP_PIN 30 // Support Extension Board +#define Z_DIR_PIN 2 +#define Z_ENABLE_PIN 31 #ifndef Z_CS_PIN - #define Z_CS_PIN 10 + #define Z_CS_PIN 10 #endif -#define E0_STEP_PIN 29 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 33 +#define E0_STEP_PIN 29 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 33 #ifndef E0_CS_PIN - #define E0_CS_PIN 14 + #define E0_CS_PIN 14 #endif -#define E1_STEP_PIN 22 -#define E1_DIR_PIN 24 -#define E1_ENABLE_PIN 26 +#define E1_STEP_PIN 22 +#define E1_DIR_PIN 24 +#define E1_ENABLE_PIN 26 #ifndef E1_CS_PIN - #define E1_CS_PIN 15 + #define E1_CS_PIN 15 #endif -#define E2_STEP_PIN 25 -#define E2_DIR_PIN 23 -#define E2_ENABLE_PIN 27 +#define E2_STEP_PIN 25 +#define E2_DIR_PIN 23 +#define E2_ENABLE_PIN 27 #ifndef E2_CS_PIN - #define E2_CS_PIN 61 + #define E2_CS_PIN 61 #endif #if HAS_CUSTOM_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 + #define Z_MIN_PROBE_PIN 49 #endif #if HAS_FILAMENT_SENSOR #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN Y_MIN_PIN + #define FIL_RUNOUT_PIN Y_MIN_PIN #endif #endif // // Heaters / Fans // -#define HEATER_0_PIN 13 -#define HEATER_1_PIN 12 -#define HEATER_2_PIN 11 -#define HEATER_BED_PIN 7 // BED H1 +#define HEATER_0_PIN 13 +#define HEATER_1_PIN 12 +#define HEATER_2_PIN 11 +#define HEATER_BED_PIN 7 // BED H1 -#define FAN_PIN 9 -#define FAN1_PIN 8 -#define CONTROLLER_FAN_PIN -1 +#define FAN_PIN 9 +#define FAN1_PIN 8 +#define CONTROLLER_FAN_PIN -1 // // Temperature Sensors // -#define TEMP_0_PIN 0 // ANALOG A0 -#define TEMP_1_PIN 1 // ANALOG A1 -#define TEMP_2_PIN 2 // ANALOG A2 -#define TEMP_3_PIN 3 // ANALOG A3 -#define TEMP_BED_PIN 4 // ANALOG A4 +#define TEMP_0_PIN 0 // ANALOG A0 +#define TEMP_1_PIN 1 // ANALOG A1 +#define TEMP_2_PIN 2 // ANALOG A2 +#define TEMP_3_PIN 3 // ANALOG A3 +#define TEMP_BED_PIN 4 // ANALOG A4 // The thermocouple uses Analog pins -#if ENABLED(VER_WITH_THERMOCOUPLE) // Defined in Configuration.h - #define TEMP_4_PIN 5 // A5 - #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) +#if ENABLED(VER_WITH_THERMOCOUPLE) // Defined in Configuration.h + #define TEMP_4_PIN 5 // A5 + #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) #endif // SPI for Max6675 or Max31855 Thermocouple /* #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define MAX6675_SS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define MAX6675_SS_PIN 49 #endif */ // // Misc. Functions // -#define SDSS 4 // 4,10,52 if using HW SPI. -#define LED_PIN -1 // 13 - HEATER_0_PIN -#define PS_ON_PIN -1 // 65 +#define SDSS 4 // 4,10,52 if using HW SPI. +#define LED_PIN -1 // 13 - HEATER_0_PIN +#define PS_ON_PIN -1 // 65 // MKS TFT / Nextion Use internal USART-1 -#define TFT_LCD_MODULE_COM 1 -#define TFT_LCD_MODULE_BAUDRATE 115200 +#define TFT_LCD_MODULE_COM 1 +#define TFT_LCD_MODULE_BAUDRATE 115200 // ESP WiFi Use internal USART-2 -#define ESP_WIFI_MODULE_COM 2 -#define ESP_WIFI_MODULE_BAUDRATE 115200 -#define ESP_WIFI_MODULE_RESET_PIN -1 -#define PIGGY_GPIO_PIN -1 +#define ESP_WIFI_MODULE_COM 2 +#define ESP_WIFI_MODULE_BAUDRATE 115200 +#define ESP_WIFI_MODULE_RESET_PIN -1 +#define PIGGY_GPIO_PIN -1 // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) -#define I2C_EEPROM // EEPROM on I2C-0 -//#define EEPROM_SD // EEPROM on SDCARD -//#define SPI_EEPROM // EEPROM on SPI-0 +#define E2END 0x7FFF // 32Kb (24lc256) +#define I2C_EEPROM // EEPROM on I2C-0 +//#define EEPROM_SD // EEPROM on SDCARD +//#define SPI_EEPROM // EEPROM on SPI-0 //#define SPI_CHAN_EEPROM1 ? //#define SPI_EEPROM1_CS ? // 2K EEPROM @@ -189,70 +189,70 @@ #if HAS_SPI_LCD #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BEEPER_PIN 62 - #define LCD_PINS_D4 48 - #define LCD_PINS_D5 50 - #define LCD_PINS_D6 52 - #define LCD_PINS_D7 53 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN 62 + #define LCD_PINS_D4 48 + #define LCD_PINS_D5 50 + #define LCD_PINS_D6 52 + #define LCD_PINS_D7 53 + #define SD_DETECT_PIN 51 #endif #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER) - #define LCD_PINS_RS 63 - #define LCD_PINS_ENABLE 64 + #define LCD_PINS_RS 63 + #define LCD_PINS_ENABLE 64 #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS 52 - #define LCD_PINS_ENABLE 53 + #define LCD_PINS_RS 52 + #define LCD_PINS_ENABLE 53 #elif HAS_SSD1306_OLED_I2C - #define BEEPER_PIN 62 - #define LCD_SDSS 10 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN 62 + #define LCD_SDSS 10 + #define SD_DETECT_PIN 51 #elif ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN 62 - #define DOGLCD_CS 64 - #define DOGLCD_A0 63 + #define BEEPER_PIN 62 + #define DOGLCD_CS 64 + #define DOGLCD_A0 63 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 48 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN 48 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 50 // D5 + #define RGB_LED_R_PIN 50 // D5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 52 // D6 + #define RGB_LED_G_PIN 52 // D6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 53 // D7 + #define RGB_LED_B_PIN 53 // D7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 50 // D5 + #define NEOPIXEL_PIN 50 // D5 #endif #elif ENABLED(MKS_MINI_12864) - #define ORIG_BEEPER_PIN 62 + #define ORIG_BEEPER_PIN 62 - #define DOGLCD_A0 52 - #define DOGLCD_CS 50 + #define DOGLCD_A0 52 + #define DOGLCD_CS 50 - #define SD_DETECT_PIN 51 + #define SD_DETECT_PIN 51 #endif #if ENABLED(NEWPANEL) - #define BTN_EN1 44 - #define BTN_EN2 42 - #define BTN_ENC 40 + #define BTN_EN1 44 + #define BTN_EN2 42 + #define BTN_ENC 40 #endif #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index db0826e7c9..ae01d5da4c 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -35,140 +35,140 @@ // Servos // #if NUM_SERVOS > 0 - #define SERVO0_PIN 11 + #define SERVO0_PIN 11 #if NUM_SERVOS > 1 - #define SERVO1_PIN 12 + #define SERVO1_PIN 12 #endif #endif // // Limit Switches // -#define X_MIN_PIN 31 -#define X_MAX_PIN 30 -#define Y_MIN_PIN 12 -#define Y_MAX_PIN 11 -#define Z_MIN_PIN 29 -#define Z_MAX_PIN 28 +#define X_MIN_PIN 31 +#define X_MAX_PIN 30 +#define Y_MIN_PIN 12 +#define Y_MAX_PIN 11 +#define Z_MIN_PIN 29 +#define Z_MAX_PIN 28 // // Steppers // -#define X_STEP_PIN 35 -#define X_DIR_PIN 34 -#define X_ENABLE_PIN 37 +#define X_STEP_PIN 35 +#define X_DIR_PIN 34 +#define X_ENABLE_PIN 37 #ifndef X_CS_PIN - #define X_CS_PIN 18 + #define X_CS_PIN 18 #endif -#define Y_STEP_PIN 22 -#define Y_DIR_PIN 23 -#define Y_ENABLE_PIN 33 +#define Y_STEP_PIN 22 +#define Y_DIR_PIN 23 +#define Y_ENABLE_PIN 33 #ifndef Y_CS_PIN - #define Y_CS_PIN 19 + #define Y_CS_PIN 19 #endif -#define Z_STEP_PIN 25 -#define Z_DIR_PIN 26 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN 25 +#define Z_DIR_PIN 26 +#define Z_ENABLE_PIN 24 #ifndef Z_CS_PIN - #define Z_CS_PIN 16 + #define Z_CS_PIN 16 #endif -#define E0_STEP_PIN 47 -#define E0_DIR_PIN 46 -#define E0_ENABLE_PIN 48 +#define E0_STEP_PIN 47 +#define E0_DIR_PIN 46 +#define E0_ENABLE_PIN 48 #ifndef E0_CS_PIN - #define E0_CS_PIN 17 + #define E0_CS_PIN 17 #endif -#define E1_STEP_PIN 44 -#define E1_DIR_PIN 36 -#define E1_ENABLE_PIN 45 +#define E1_STEP_PIN 44 +#define E1_DIR_PIN 36 +#define E1_ENABLE_PIN 45 #ifndef E1_CS_PIN - #define E1_CS_PIN -1 + #define E1_CS_PIN -1 #endif -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 41 -#define E2_ENABLE_PIN 43 +#define E2_STEP_PIN 42 +#define E2_DIR_PIN 41 +#define E2_ENABLE_PIN 43 #ifndef E2_CS_PIN - #define E2_CS_PIN -1 + #define E2_CS_PIN -1 #endif -#define E3_STEP_PIN 39 -#define E3_DIR_PIN 38 -#define E3_ENABLE_PIN 40 +#define E3_STEP_PIN 39 +#define E3_DIR_PIN 38 +#define E3_ENABLE_PIN 40 #ifndef E3_CS_PIN - #define E3_CS_PIN -1 + #define E3_CS_PIN -1 #endif // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 2 // Analog Input -#define TEMP_2_PIN 3 // Analog Input -#define TEMP_3_PIN 4 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 2 // Analog Input +#define TEMP_2_PIN 3 // Analog Input +#define TEMP_3_PIN 4 // Analog Input +#define TEMP_BED_PIN 1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_1_PIN 8 -#define HEATER_2_PIN 7 -#define HEATER_3_PIN 9 -#define HEATER_BED_PIN 2 +#define HEATER_0_PIN 3 +#define HEATER_1_PIN 8 +#define HEATER_2_PIN 7 +#define HEATER_3_PIN 9 +#define HEATER_BED_PIN 2 #ifndef FAN_PIN - #define FAN_PIN 6 + #define FAN_PIN 6 #endif -#define FAN2_PIN 5 +#define FAN2_PIN 5 // // Misc. Functions // -#define SDSS 59 -#define SD_DETECT_PIN 60 -#define LED_PIN 13 -#define PS_ON_PIN 32 +#define SDSS 59 +#define SD_DETECT_PIN 60 +#define LED_PIN 13 +#define PS_ON_PIN 32 // // SPI Buses // -#define DAC0_SYNC 53 // PB14 -#define SPI_CHAN_DAC 1 +#define DAC0_SYNC 53 // PB14 +#define SPI_CHAN_DAC 1 -#define SPI_CHAN_EEPROM1 -1 -#define SPI_EEPROM1_CS -1 -#define SPI_EEPROM2_CS -1 -#define SPI_FLASH_CS -1 +#define SPI_CHAN_EEPROM1 -1 +#define SPI_EEPROM1_CS -1 +#define SPI_EEPROM2_CS -1 +#define SPI_FLASH_CS -1 // SPI for Max6675 or Max31855 Thermocouple -#define MAX6675_SS_PIN 65 -#define MAX31855_SS0 65 -#define MAX31855_SS1 52 -#define MAX31855_SS2 50 -#define MAX31855_SS3 51 +#define MAX6675_SS_PIN 65 +#define MAX31855_SS0 65 +#define MAX31855_SS1 52 +#define MAX31855_SS2 50 +#define MAX31855_SS3 51 -#define ENC424_SS 61 +#define ENC424_SS 61 // // LCD / Controller // -#define BEEPER_PIN 27 +#define BEEPER_PIN 27 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS A8 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE MOSI // SID (MOSI) - #define LCD_PINS_D4 SCK // SCK (CLK) clock + #define LCD_PINS_RS A8 // CS chip select / SS chip slave select + #define LCD_PINS_ENABLE MOSI // SID (MOSI) + #define LCD_PINS_D4 SCK // SCK (CLK) clock - #define BTN_EN1 20 - #define BTN_EN2 21 - #define BTN_ENC 64 + #define BTN_EN1 20 + #define BTN_EN2 21 + #define BTN_ENC 64 #endif // REPRAPWORLD_GRAPHICAL_LCD diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 20da59e395..b7d5172e0d 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -36,110 +36,110 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN 6 -#define SERVO2_PIN 5 -#define SERVO3_PIN 4 +#define SERVO0_PIN 11 +#define SERVO1_PIN 6 +#define SERVO2_PIN 5 +#define SERVO3_PIN 4 // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) -#define I2C_EEPROM // EEPROM on I2C-0 +#define E2END 0x7FFF // 32Kb (24lc256) +#define I2C_EEPROM // EEPROM on I2C-0 // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN 3 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 18 + #define Z_MIN_PROBE_PIN 18 #endif // // Steppers // -#define X_STEP_PIN 67 // Mega/Due:54 - AGCM4:67 -#define X_DIR_PIN 68 // Mega/Due:55 - AGCM4:68 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN 67 // Mega/Due:54 - AGCM4:67 +#define X_DIR_PIN 68 // Mega/Due:55 - AGCM4:68 +#define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 47 + #define X_CS_PIN 47 #endif -#define Y_STEP_PIN 73 // Mega/Due:60 - AGCM4:73 -#define Y_DIR_PIN 74 // Mega/Due:61 - AGCM4:74 -#define Y_ENABLE_PIN 69 // Mega/Due:56 - AGCM4:69 +#define Y_STEP_PIN 73 // Mega/Due:60 - AGCM4:73 +#define Y_DIR_PIN 74 // Mega/Due:61 - AGCM4:74 +#define Y_ENABLE_PIN 69 // Mega/Due:56 - AGCM4:69 #ifndef Y_CS_PIN - #define Y_CS_PIN 45 + #define Y_CS_PIN 45 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 54 // Mega/Due:62 - AGCM4:54 +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 54 // Mega/Due:62 - AGCM4:54 #ifndef Z_CS_PIN - #define Z_CS_PIN 32 + #define Z_CS_PIN 32 #endif -#define Z2_STEP_PIN 36 -#define Z2_DIR_PIN 34 -#define Z2_ENABLE_PIN 30 +#define Z2_STEP_PIN 36 +#define Z2_DIR_PIN 34 +#define Z2_ENABLE_PIN 30 #ifndef Z2_CS_PIN - #define Z2_CS_PIN 22 + #define Z2_CS_PIN 22 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 #ifndef E0_CS_PIN - #define E0_CS_PIN 43 + #define E0_CS_PIN 43 #endif // // Temperature Sensors // -#define TEMP_0_PIN 13 -#define TEMP_BED_PIN 14 -#define TEMP_CHAMBER_PIN 15 +#define TEMP_0_PIN 13 +#define TEMP_BED_PIN 14 +#define TEMP_CHAMBER_PIN 15 // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_BED_PIN 8 -#define FAN_PIN 9 -#define FAN1_PIN 7 -#define FAN2_PIN 12 +#define HEATER_0_PIN 10 +#define HEATER_BED_PIN 8 +#define FAN_PIN 9 +#define FAN1_PIN 7 +#define FAN2_PIN 12 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS 53 +#define LED_PIN 13 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif // RAMPS 1.4 DIO 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 4 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 39 + #define PS_ON_PIN 39 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) - #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #if NUM_SERVOS <= 1 // Prefer the servo connector + #define CASE_LIGHT_PIN 6 // Hardware PWM #endif #endif @@ -147,10 +147,10 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) - #if !NUM_SERVOS // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #if !NUM_SERVOS // Use servo connector if possible + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_DIR_PIN 5 #else #error "No auto-assignable Spindle/Laser pins available." #endif @@ -161,13 +161,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 58 // Mega/Due:66 - AGCM4:58 + #define TMC_SW_MOSI 58 // Mega/Due:66 - AGCM4:58 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 + #define TMC_SW_MISO 44 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK 56 // Mega/Due:64 - AGCM4:56 + #define TMC_SW_SCK 56 // Mega/Due:64 - AGCM4:56 #endif #endif @@ -195,91 +195,91 @@ // #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 47 + #define X_SERIAL_TX_PIN 47 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 47 + #define X_SERIAL_RX_PIN 47 #endif #ifndef X2_SERIAL_TX_PIN - #define X2_SERIAL_TX_PIN -1 + #define X2_SERIAL_TX_PIN -1 #endif #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN -1 + #define X2_SERIAL_RX_PIN -1 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 45 + #define Y_SERIAL_TX_PIN 45 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 45 + #define Y_SERIAL_RX_PIN 45 #endif #ifndef Y2_SERIAL_TX_PIN - #define Y2_SERIAL_TX_PIN -1 + #define Y2_SERIAL_TX_PIN -1 #endif #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN -1 + #define Y2_SERIAL_RX_PIN -1 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 32 + #define Z_SERIAL_TX_PIN 32 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 32 + #define Z_SERIAL_RX_PIN 32 #endif #ifndef Z2_SERIAL_TX_PIN - #define Z2_SERIAL_TX_PIN 22 + #define Z2_SERIAL_TX_PIN 22 #endif #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN 22 + #define Z2_SERIAL_RX_PIN 22 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 43 + #define E0_SERIAL_TX_PIN 43 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 43 + #define E0_SERIAL_RX_PIN 43 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN -1 + #define E1_SERIAL_TX_PIN -1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 + #define E1_SERIAL_RX_PIN -1 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN -1 + #define E2_SERIAL_TX_PIN -1 #endif #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 + #define E2_SERIAL_RX_PIN -1 #endif #ifndef E3_SERIAL_TX_PIN - #define E3_SERIAL_TX_PIN -1 + #define E3_SERIAL_TX_PIN -1 #endif #ifndef E3_SERIAL_RX_PIN - #define E3_SERIAL_RX_PIN -1 + #define E3_SERIAL_RX_PIN -1 #endif #ifndef E4_SERIAL_TX_PIN - #define E4_SERIAL_TX_PIN -1 + #define E4_SERIAL_TX_PIN -1 #endif #ifndef E4_SERIAL_RX_PIN - #define E4_SERIAL_RX_PIN -1 + #define E4_SERIAL_RX_PIN -1 #endif #ifndef E5_SERIAL_TX_PIN - #define E5_SERIAL_TX_PIN -1 + #define E5_SERIAL_TX_PIN -1 #endif #ifndef E5_SERIAL_RX_PIN - #define E5_SERIAL_RX_PIN -1 + #define E5_SERIAL_RX_PIN -1 #endif #ifndef E6_SERIAL_TX_PIN - #define E6_SERIAL_TX_PIN -1 + #define E6_SERIAL_TX_PIN -1 #endif #ifndef E6_SERIAL_RX_PIN - #define E6_SERIAL_RX_PIN -1 + #define E6_SERIAL_RX_PIN -1 #endif #ifndef E7_SERIAL_TX_PIN - #define E7_SERIAL_TX_PIN -1 + #define E7_SERIAL_TX_PIN -1 #endif #ifndef E7_SERIAL_RX_PIN - #define E7_SERIAL_RX_PIN -1 + #define E7_SERIAL_RX_PIN -1 #endif #endif @@ -345,17 +345,17 @@ // #define DOGLCD_SCK 23 // #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 29 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #endif #endif @@ -363,10 +363,10 @@ #if DISABLED(NEWPANEL) // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK 38 + //#define SHIFT_LD 42 + //#define SHIFT_OUT 40 + //#define SHIFT_EN 17 #endif #endif @@ -378,22 +378,22 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 #if ENABLED(CR10_STOCKDISPLAY) // TO TEST // #define BTN_EN1 17 // #define BTN_EN2 23 #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 31 + #define BTN_EN2 33 #endif - #define BTN_ENC 35 + #define BTN_ENC 35 #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #endif - #define KILL_PIN 41 + #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) // TO TEST @@ -465,15 +465,15 @@ #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST - //#define BEEPER_PIN 37 - //#define BTN_ENC 35 - //#define SD_DETECT_PIN 49 + //#define BEEPER_PIN 37 + //#define BTN_ENC 35 + //#define SD_DETECT_PIN 49 //#ifndef KILL_PIN // #define KILL_PIN 41 //#endif - #if ENABLED(MKS_MINI_12864) // Added in Marlin 1.1.6 + #if ENABLED(MKS_MINI_12864) // Added in Marlin 1.1.6 // TO TEST // #define DOGLCD_A0 27 @@ -502,8 +502,8 @@ // #define BTN_EN1 33 // #define BTN_EN2 31 - //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems - // results in LCD soft SPI mode 3, SD soft SPI mode 0 + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 // #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. @@ -600,12 +600,12 @@ // SD Support // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) #undef SDSS - #define SDSS 83 + #define SDSS 83 #undef SD_DETECT_PIN - #define SD_DETECT_PIN 95 + #define SD_DETECT_PIN 95 #endif diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index ebd0503712..73145a3cdb 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -98,50 +98,50 @@ // // Limit Switches // -#define X_STOP_PIN 18 -#define Y_STOP_PIN 19 -#define Z_STOP_PIN 20 +#define X_STOP_PIN 18 +#define Y_STOP_PIN 19 +#define Z_STOP_PIN 20 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 21 -#define X_ENABLE_PIN 14 +#define X_STEP_PIN 15 +#define X_DIR_PIN 21 +#define X_ENABLE_PIN 14 -#define Y_STEP_PIN 22 -#define Y_DIR_PIN 23 -#define Y_ENABLE_PIN 14 +#define Y_STEP_PIN 22 +#define Y_DIR_PIN 23 +#define Y_ENABLE_PIN 14 -#define Z_STEP_PIN 3 -#define Z_DIR_PIN 2 -#define Z_ENABLE_PIN 26 +#define Z_STEP_PIN 3 +#define Z_DIR_PIN 2 +#define Z_ENABLE_PIN 26 -#define E0_STEP_PIN 1 -#define E0_DIR_PIN 0 -#define E0_ENABLE_PIN 14 +#define E0_STEP_PIN 1 +#define E0_DIR_PIN 0 +#define E0_ENABLE_PIN 14 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) +#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) // // Heaters / Fans // -#define HEATER_0_PIN 13 // (extruder) -#define HEATER_BED_PIN 12 // (bed) +#define HEATER_0_PIN 13 // (extruder) +#define HEATER_BED_PIN 12 // (bed) #ifndef FAN_PIN - #define FAN_PIN 4 + #define FAN_PIN 4 #endif // // Misc. Functions // -#define SDSS 31 -#define LED_PIN -1 +#define SDSS 31 +#define LED_PIN -1 /** * LCD / Controller @@ -153,36 +153,36 @@ */ #if HAS_SPI_LCD - #define LCD_SDSS 28 + #define LCD_SDSS 28 #if ENABLED(ADC_KEYPAD) - #define SERVO0_PIN 27 // free for BLTouch/3D-Touch - #define LCD_PINS_RS 28 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 16 - #define LCD_PINS_D7 17 - #define ADC_KEYPAD_PIN 1 + #define SERVO0_PIN 27 // free for BLTouch/3D-Touch + #define LCD_PINS_RS 28 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 10 + #define LCD_PINS_D5 11 + #define LCD_PINS_D6 16 + #define LCD_PINS_D7 17 + #define ADC_KEYPAD_PIN 1 #elif EITHER(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, ANET_FULL_GRAPHICS_LCD) // Pin definitions for the Anet A6 Full Graphics display and the RepRapDiscount Full Graphics // display using an adapter board // https://go.aisler.net/benlye/anet-lcd-adapter/pcb // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 - #define SERVO0_PIN 29 // free for BLTouch/3D-Touch - #define BEEPER_PIN 17 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 28 - #define LCD_PINS_D4 30 - #define BTN_EN1 11 - #define BTN_EN2 10 - #define BTN_ENC 16 + #define SERVO0_PIN 29 // free for BLTouch/3D-Touch + #define BEEPER_PIN 17 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 28 + #define LCD_PINS_D4 30 + #define BTN_EN1 11 + #define BTN_EN2 10 + #define BTN_ENC 16 #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #define BOARD_ST7920_DELAY_2 DELAY_NS(63) #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #define STD_ENCODER_PULSES_PER_STEP 4 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 #endif #else - #define SERVO0_PIN 27 + #define SERVO0_PIN 27 #endif /** diff --git a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h index 833f99fb7f..b9a917d65d 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h @@ -55,47 +55,47 @@ #endif #define BOARD_INFO_NAME "Gen3 Monolithic" -#define DEBUG_PIN 0 +#define DEBUG_PIN 0 // // Limit Switches // -#define X_STOP_PIN 20 -#define Y_STOP_PIN 25 -#define Z_STOP_PIN 30 +#define X_STOP_PIN 20 +#define Y_STOP_PIN 25 +#define Z_STOP_PIN 30 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 // actually uses Y_enable_pin +#define X_STEP_PIN 15 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 24 // actually uses Y_enable_pin -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 // shared with X_enable_pin +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 // shared with X_enable_pin -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 +#define Z_STEP_PIN 27 +#define Z_DIR_PIN 28 +#define Z_ENABLE_PIN 29 -#define E0_STEP_PIN 12 -#define E0_DIR_PIN 17 -#define E0_ENABLE_PIN 3 +#define E0_STEP_PIN 12 +#define E0_DIR_PIN 17 +#define E0_ENABLE_PIN 3 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input +#define TEMP_0_PIN 0 // Analog Input // // Heaters // -#define HEATER_0_PIN 16 +#define HEATER_0_PIN 16 // // Misc. Functions // -#define PS_ON_PIN 14 // Alex, does this work on the card? +#define PS_ON_PIN 14 // Alex, does this work on the card? // Alex extras from Gen3+ diff --git a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h index c7c037fd4d..6cd6fdaf27 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h @@ -50,7 +50,6 @@ * */ - #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" #endif @@ -60,43 +59,43 @@ // // Limit Switches // -#define X_STOP_PIN 20 -#define Y_STOP_PIN 25 -#define Z_STOP_PIN 30 +#define X_STOP_PIN 20 +#define Y_STOP_PIN 25 +#define Z_STOP_PIN 30 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 19 +#define X_STEP_PIN 15 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 19 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 +#define Z_STEP_PIN 27 +#define Z_DIR_PIN 28 +#define Z_ENABLE_PIN 29 -#define E0_STEP_PIN 17 -#define E0_DIR_PIN 21 -#define E0_ENABLE_PIN 13 +#define E0_STEP_PIN 17 +#define E0_DIR_PIN 21 +#define E0_ENABLE_PIN 13 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN 5 // Analog Input (pin 34 bed) +#define TEMP_0_PIN 0 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN 5 // Analog Input (pin 34 bed) // // Heaters // -#define HEATER_0_PIN 12 -#define HEATER_BED_PIN 16 +#define HEATER_0_PIN 12 +#define HEATER_BED_PIN 16 // // Misc. Functions // -#define SDSS 4 -#define PS_ON_PIN 14 +#define SDSS 4 +#define PS_ON_PIN 14 diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index d1b8391bcd..0d2449ae6e 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -63,58 +63,58 @@ // // Limit Switches // -#define X_STOP_PIN 20 -#define Y_STOP_PIN 25 -#define Z_STOP_PIN 30 +#define X_STOP_PIN 20 +#define Y_STOP_PIN 25 +#define Z_STOP_PIN 30 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 19 +#define X_STEP_PIN 15 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 19 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 +#define Z_STEP_PIN 27 +#define Z_DIR_PIN 28 +#define Z_ENABLE_PIN 29 -#define E0_STEP_PIN 4 // Edited @ EJE Electronics 20100715 -#define E0_DIR_PIN 2 // Edited @ EJE Electronics 20100715 -#define E0_ENABLE_PIN 3 // Added @ EJE Electronics 20100715 +#define E0_STEP_PIN 4 // Edited @ EJE Electronics 20100715 +#define E0_DIR_PIN 2 // Edited @ EJE Electronics 20100715 +#define E0_ENABLE_PIN 3 // Added @ EJE Electronics 20100715 // // Temperature Sensor // -#define TEMP_0_PIN 5 // Analog Input +#define TEMP_0_PIN 5 // Analog Input // // Heaters // -#define HEATER_0_PIN 14 // changed @ rkoeppl 20110410 +#define HEATER_0_PIN 14 // changed @ rkoeppl 20110410 #if !MB(GEN6) - #define HEATER_BED_PIN 1 // changed @ rkoeppl 20110410 - #define TEMP_BED_PIN 0 // Analog Input + #define HEATER_BED_PIN 1 // changed @ rkoeppl 20110410 + #define TEMP_BED_PIN 0 // Analog Input #endif // // Misc. Functions // -#define SDSS 17 -#define DEBUG_PIN 0 -#define CASE_LIGHT_PIN 16 // Hardware PWM +#define SDSS 17 +#define DEBUG_PIN 0 +#define CASE_LIGHT_PIN 16 // Hardware PWM // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 6 +#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM +#define SPINDLE_DIR_PIN 6 diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index 4ab53faa98..bb0e44a300 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -61,90 +61,89 @@ #endif #ifndef GEN7_VERSION - #define GEN7_VERSION 12 // v1.x + #define GEN7_VERSION 12 // v1.x #endif // // Limit Switches // -#define X_MIN_PIN 7 -#define Y_MIN_PIN 5 -#define Z_MIN_PIN 1 -#define Z_MAX_PIN 0 -#define Y_MAX_PIN 2 -#define X_MAX_PIN 6 - +#define X_MIN_PIN 7 +#define Y_MIN_PIN 5 +#define Z_MIN_PIN 1 +#define Z_MAX_PIN 0 +#define Y_MAX_PIN 2 +#define X_MAX_PIN 6 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 0 + #define Z_MIN_PROBE_PIN 0 #endif // // Steppers // -#define X_STEP_PIN 19 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 19 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN 26 +#define Z_DIR_PIN 25 +#define Z_ENABLE_PIN 24 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 24 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 -#if !defined(FAN_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin - #define FAN_PIN 31 +#if !defined(FAN_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin + #define FAN_PIN 31 #endif // // Misc. Functions // -#define PS_ON_PIN 15 +#define PS_ON_PIN 15 #if GEN7_VERSION < 13 - #define CASE_LIGHT_PIN 16 // Hardware PWM -#else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header - #define CASE_LIGHT_PIN 15 // Hardware PWM + #define CASE_LIGHT_PIN 16 // Hardware PWM +#else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header + #define CASE_LIGHT_PIN 15 // Hardware PWM #endif // All these generations of Gen7 supply thermistor power // via PS_ON, so ignore bad thermistor readings -//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#define DEBUG_PIN 0 +#define DEBUG_PIN 0 // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! -#define SPINDLE_DIR_PIN 11 +#define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! +#define SPINDLE_DIR_PIN 11 #if GEN7_VERSION < 13 - #define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header - #define SPINDLE_LASER_PWM_PIN 15 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM +#else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header + #define SPINDLE_LASER_PWM_PIN 15 // Hardware PWM #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index 5121b7d2e9..9dc9f2808b 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -58,62 +58,62 @@ #define BOARD_INFO_NAME "Gen7 v1.4" -#define GEN7_VERSION 14 // v1.4 +#define GEN7_VERSION 14 // v1.4 // // Limit switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 // // Steppers // -#define X_STEP_PIN 29 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 25 +#define X_STEP_PIN 29 +#define X_DIR_PIN 28 +#define X_ENABLE_PIN 25 -#define Y_STEP_PIN 27 -#define Y_DIR_PIN 26 -#define Y_ENABLE_PIN 25 +#define Y_STEP_PIN 27 +#define Y_DIR_PIN 26 +#define Y_ENABLE_PIN 25 -#define Z_STEP_PIN 23 -#define Z_DIR_PIN 22 -#define Z_ENABLE_PIN 25 +#define Z_STEP_PIN 23 +#define Z_DIR_PIN 22 +#define Z_ENABLE_PIN 25 -#define E0_STEP_PIN 19 -#define E0_DIR_PIN 18 -#define E0_ENABLE_PIN 25 +#define E0_STEP_PIN 19 +#define E0_DIR_PIN 18 +#define E0_ENABLE_PIN 25 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 // // Misc. Functions // -#define PS_ON_PIN 15 -#define CASE_LIGHT_PIN 15 // Hardware PWM +#define PS_ON_PIN 15 +#define CASE_LIGHT_PIN 15 // Hardware PWM // A pin for debugging -#define DEBUG_PIN 0 +#define DEBUG_PIN 0 // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 20 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 21 +#define SPINDLE_LASER_ENA_PIN 20 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM +#define SPINDLE_DIR_PIN 21 diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 0f8a92f08d..67a9762fa0 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -64,76 +64,76 @@ // // Limit Switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 // // Steppers // -#define X_STEP_PIN 21 // different from standard GEN7 -#define X_DIR_PIN 20 // different from standard GEN7 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 21 // different from standard GEN7 +#define X_DIR_PIN 20 // different from standard GEN7 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN 26 +#define Z_DIR_PIN 25 +#define Z_ENABLE_PIN 24 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 24 // // Temperature Sensors // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input (pin 34 bed) +#define TEMP_0_PIN 2 // Analog Input +#define TEMP_BED_PIN 1 // Analog Input (pin 34 bed) // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 // (bed) +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 // (bed) // // Misc. Functions // -#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support -#define PS_ON_PIN 19 -#define CASE_LIGHT_PIN 15 // Hardware PWM +#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support +#define PS_ON_PIN 19 +#define CASE_LIGHT_PIN 15 // Hardware PWM // A pin for debugging -#define DEBUG_PIN -1 +#define DEBUG_PIN -1 // // LCD / Controller // -#define BEEPER_PIN -1 +#define BEEPER_PIN -1 // 4bit LCD Support -#define LCD_PINS_RS 18 -#define LCD_PINS_ENABLE 17 -#define LCD_PINS_D4 16 -#define LCD_PINS_D5 15 -#define LCD_PINS_D6 13 -#define LCD_PINS_D7 14 +#define LCD_PINS_RS 18 +#define LCD_PINS_ENABLE 17 +#define LCD_PINS_D4 16 +#define LCD_PINS_D5 15 +#define LCD_PINS_D6 13 +#define LCD_PINS_D7 14 // Buttons are directly attached -#define BTN_EN1 11 -#define BTN_EN2 10 -#define BTN_ENC 12 +#define BTN_EN1 11 +#define BTN_EN2 10 +#define BTN_ENC 12 // RS485 pins -//#define TX_ENABLE_PIN 12 -//#define RX_ENABLE_PIN 13 +//#define TX_ENABLE_PIN 12 +//#define RX_ENABLE_PIN 13 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 6 +#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM +#define SPINDLE_DIR_PIN 6 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 958ea78da4..10a52705e7 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -46,15 +46,15 @@ #undef LCD_PINS_D5 #undef LCD_PINS_D6 #undef LCD_PINS_D7 -#undef FIL_RUNOUT_PIN // Uses Beeper/LED Pin Pulled to GND +#undef FIL_RUNOUT_PIN // Uses Beeper/LED Pin Pulled to GND -#define LCD_SDSS 31 // Smart Controller SD card reader (rather than the Melzi) -#define LCD_PINS_RS 28 // ST9720 CS -#define LCD_PINS_ENABLE 17 // ST9720 DAT -#define LCD_PINS_D4 30 // ST9720 CLK +#define LCD_SDSS 31 // Smart Controller SD card reader (rather than the Melzi) +#define LCD_PINS_RS 28 // ST9720 CS +#define LCD_PINS_ENABLE 17 // ST9720 DAT +#define LCD_PINS_D4 30 // ST9720 CLK #if ENABLED(BLTOUCH) - #define SERVO0_PIN 27 + #define SERVO0_PIN 27 #undef BEEPER_PIN #endif @@ -67,7 +67,7 @@ #if ENABLED(MINIPANEL) #undef DOGLCD_CS - #define DOGLCD_CS LCD_PINS_RS + #define DOGLCD_CS LCD_PINS_RS #endif /** diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index bf0e34a9ec..8e682453b4 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -36,12 +36,12 @@ #undef BTN_EN2 #undef BTN_ENC -#define LCD_PINS_RS 17 // ST9720 CS -#define LCD_PINS_ENABLE 16 // ST9720 DAT -#define LCD_PINS_D4 11 // ST9720 CLK -#define BTN_EN1 30 -#define BTN_EN2 29 -#define BTN_ENC 28 +#define LCD_PINS_RS 17 // ST9720 CS +#define LCD_PINS_ENABLE 16 // ST9720 DAT +#define LCD_PINS_D4 11 // ST9720 CLK +#define BTN_EN1 30 +#define BTN_EN2 29 +#define BTN_ENC 28 // Alter timing for graphical display #if HAS_GRAPHICAL_LCD diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index 50433f6244..88b80dfb89 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -40,16 +40,16 @@ #undef BTN_ENC #undef LCD_SDSS -#define Z_ENABLE_PIN 14 -#define LCD_PINS_RS 30 -#define LCD_PINS_ENABLE 28 -#define LCD_PINS_D4 16 -#define LCD_PINS_D5 17 -#define LCD_PINS_D6 27 -#define LCD_PINS_D7 29 -#define BTN_EN1 10 -#define BTN_EN2 11 -#define BTN_ENC 26 +#define Z_ENABLE_PIN 14 +#define LCD_PINS_RS 30 +#define LCD_PINS_ENABLE 28 +#define LCD_PINS_D4 16 +#define LCD_PINS_D5 17 +#define LCD_PINS_D6 27 +#define LCD_PINS_D7 29 +#define BTN_EN1 10 +#define BTN_EN2 11 +#define BTN_ENC 26 #if HAS_GRAPHICAL_LCD #define BOARD_ST7920_DELAY_1 DELAY_NS(0) diff --git a/Marlin/src/pins/sanguino/pins_OMCA.h b/Marlin/src/pins/sanguino/pins_OMCA.h index c2ba1ed707..774910bd7d 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA.h +++ b/Marlin/src/pins/sanguino/pins_OMCA.h @@ -86,66 +86,66 @@ // // Limit Switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 25 -#define X_ENABLE_PIN 10 +#define X_STEP_PIN 26 +#define X_DIR_PIN 25 +#define X_ENABLE_PIN 10 -#define Y_STEP_PIN 28 -#define Y_DIR_PIN 27 -#define Y_ENABLE_PIN 10 +#define Y_STEP_PIN 28 +#define Y_DIR_PIN 27 +#define Y_ENABLE_PIN 10 -#define Z_STEP_PIN 23 -#define Z_DIR_PIN 22 -#define Z_ENABLE_PIN 10 +#define Z_STEP_PIN 23 +#define Z_DIR_PIN 22 +#define Z_ENABLE_PIN 10 -#define E0_STEP_PIN 24 -#define E0_DIR_PIN 21 -#define E0_ENABLE_PIN 10 +#define E0_STEP_PIN 24 +#define E0_DIR_PIN 21 +#define E0_ENABLE_PIN 10 -#define E1_STEP_PIN -1 // 21 -#define E1_DIR_PIN -1 // 20 -#define E1_ENABLE_PIN -1 // 19 +#define E1_STEP_PIN -1 // 21 +#define E1_DIR_PIN -1 // 20 +#define E1_ENABLE_PIN -1 // 19 -#define E2_STEP_PIN -1 // 21 -#define E2_DIR_PIN -1 // 20 -#define E2_ENABLE_PIN -1 // 18 +#define E2_STEP_PIN -1 // 21 +#define E2_DIR_PIN -1 // 20 +#define E2_ENABLE_PIN -1 // 18 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input (1,2 or I2C) +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input (1,2 or I2C) // // Heaters / Fans // -#define HEATER_0_PIN 3 // DONE PWM on RIGHT connector -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN 3 // DONE PWM on RIGHT connector +#define HEATER_BED_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 14 // PWM on MIDDLE connector + #define FAN_PIN 14 // PWM on MIDDLE connector #endif // // Misc. Functions // -#define SDSS 11 +#define SDSS 11 -#define I2C_SCL_PIN 16 -#define I2C_SDA_PIN 17 +#define I2C_SCL_PIN 16 +#define I2C_SDA_PIN 17 // future proofing -#define __FS 20 -#define __FD 19 -#define __GS 18 -#define __GD 13 +#define __FS 20 +#define __FD 19 +#define __GS 18 +#define __GD 13 -#define UNUSED_PWM 14 // PWM on LEFT connector +#define UNUSED_PWM 14 // PWM on LEFT connector diff --git a/Marlin/src/pins/sanguino/pins_OMCA_A.h b/Marlin/src/pins/sanguino/pins_OMCA_A.h index b8340a3deb..73237743b8 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA_A.h +++ b/Marlin/src/pins/sanguino/pins_OMCA_A.h @@ -85,54 +85,54 @@ // // Limit Switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 // // Steppers // -#define X_STEP_PIN 21 -#define X_DIR_PIN 20 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 21 +#define X_DIR_PIN 20 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN 26 +#define Z_DIR_PIN 25 +#define Z_ENABLE_PIN 24 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 24 -#define E1_STEP_PIN -1 // 19 -#define E1_DIR_PIN -1 // 18 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN -1 // 19 +#define E1_DIR_PIN -1 // 18 +#define E1_ENABLE_PIN 24 -#define E2_STEP_PIN -1 // 17 -#define E2_DIR_PIN -1 // 16 -#define E2_ENABLE_PIN 24 +#define E2_STEP_PIN -1 // 17 +#define E2_DIR_PIN -1 // 16 +#define E2_ENABLE_PIN 24 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input (D27) +#define TEMP_0_PIN 0 // Analog Input (D27) // // Heaters / Fans // -#define HEATER_0_PIN 4 +#define HEATER_0_PIN 4 #ifndef FAN_PIN - #define FAN_PIN 3 + #define FAN_PIN 3 #endif // // Misc. Functions // -#define SDSS 11 +#define SDSS 11 /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 977ba16daf..50d3a53779 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -63,60 +63,60 @@ // // Limit Switches // -#define X_STOP_PIN 18 -#define Y_STOP_PIN 19 -#define Z_STOP_PIN 20 +#define X_STOP_PIN 18 +#define Y_STOP_PIN 19 +#define Z_STOP_PIN 20 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 21 +#define X_STEP_PIN 15 +#define X_DIR_PIN 21 -#define Y_STEP_PIN 22 -#define Y_DIR_PIN 23 +#define Y_STEP_PIN 22 +#define Y_DIR_PIN 23 -#define Z_STEP_PIN 3 -#define Z_DIR_PIN 2 +#define Z_STEP_PIN 3 +#define Z_DIR_PIN 2 -#define E0_STEP_PIN 1 -#define E0_DIR_PIN 0 +#define E0_STEP_PIN 1 +#define E0_DIR_PIN 0 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) +#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) // // Heaters / Fans // -#define HEATER_0_PIN 13 // (extruder) +#define HEATER_0_PIN 13 // (extruder) #if ENABLED(SANGUINOLOLU_V_1_2) - #define HEATER_BED_PIN 12 // (bed) - #define X_ENABLE_PIN 14 - #define Y_ENABLE_PIN 14 - #define Z_ENABLE_PIN 26 - #define E0_ENABLE_PIN 14 + #define HEATER_BED_PIN 12 // (bed) + #define X_ENABLE_PIN 14 + #define Y_ENABLE_PIN 14 + #define Z_ENABLE_PIN 26 + #define E0_ENABLE_PIN 14 #if !defined(FAN_PIN) && ENABLED(LCD_I2C_PANELOLU2) - #define FAN_PIN 4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan + #define FAN_PIN 4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan #endif #else - #define HEATER_BED_PIN 14 // (bed) - #define X_ENABLE_PIN -1 - #define Y_ENABLE_PIN -1 - #define Z_ENABLE_PIN -1 - #define E0_ENABLE_PIN -1 + #define HEATER_BED_PIN 14 // (bed) + #define X_ENABLE_PIN -1 + #define Y_ENABLE_PIN -1 + #define Z_ENABLE_PIN -1 + #define E0_ENABLE_PIN -1 #endif #if !defined(FAN_PIN) && (MB(AZTEEG_X1, STB_11) || IS_MELZI) - #define FAN_PIN 4 // Works for Panelolu2 too + #define FAN_PIN 4 // Works for Panelolu2 too #endif // @@ -129,17 +129,17 @@ * If you encounter issues with these pins, upgrade your * Sanguino libraries! See #368. */ -//#define SDSS 24 -#define SDSS 31 +//#define SDSS 24 +#define SDSS 31 #if IS_MELZI - #define LED_PIN 27 + #define LED_PIN 27 #elif MB(STB_11) - #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED + #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED #endif -#if NONE(SPINDLE_FEATURE, LASER_FEATURE) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL) // try to use IO Header - #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available +#if NONE(SPINDLE_FEATURE, LASER_FEATURE) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL)// try to use IO Header + #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available #endif /** @@ -156,57 +156,57 @@ // #if HAS_SPI_LCD - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #if HAS_GRAPHICAL_LCD #if ENABLED(LCD_FOR_MELZI) - #define LCD_PINS_RS 17 - #define LCD_PINS_ENABLE 16 - #define LCD_PINS_D4 11 + #define LCD_PINS_RS 17 + #define LCD_PINS_ENABLE 16 + #define LCD_PINS_D4 11 #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #define BOARD_ST7920_DELAY_2 DELAY_NS(188) #define BOARD_ST7920_DELAY_3 DELAY_NS(0) - #elif ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 + #elif ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI - #define LCD_PINS_RS 30 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 29 // SID (MOSI) - #define LCD_PINS_D4 17 // SCK (CLK) clock + #define LCD_PINS_RS 30 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 29 // SID (MOSI) + #define LCD_PINS_D4 17 // SCK (CLK) clock // Pin 27 is taken by LED_PIN, but Melzi LED does nothing with // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. - #define BEEPER_PIN 27 - #else // Sanguinololu >=1.3 - #define LCD_PINS_RS 4 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 29 - #define LCD_PINS_D6 28 - #define LCD_PINS_D7 27 + #define BEEPER_PIN 27 + #else // Sanguinololu >=1.3 + #define LCD_PINS_RS 4 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 30 + #define LCD_PINS_D5 29 + #define LCD_PINS_D6 28 + #define LCD_PINS_D7 27 #endif #else - #define DOGLCD_A0 30 + #define DOGLCD_A0 30 #if ENABLED(MAKRPANEL) - #define BEEPER_PIN 29 - #define DOGLCD_CS 17 - #define LCD_BACKLIGHT_PIN 28 // PA3 + #define BEEPER_PIN 29 + #define DOGLCD_CS 17 + #define LCD_BACKLIGHT_PIN 28 // PA3 #elif IS_MELZI - #define BEEPER_PIN 27 - #define DOGLCD_CS 28 + #define BEEPER_PIN 27 + #define DOGLCD_CS 28 - #else // !MAKRPANEL + #else // !MAKRPANEL - #define DOGLCD_CS 29 + #define DOGLCD_CS 29 #endif @@ -218,57 +218,57 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards + #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define LCD_PINS_RS 28 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 16 - #define LCD_PINS_D7 17 + #define LCD_PINS_RS 28 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 10 + #define LCD_PINS_D5 11 + #define LCD_PINS_D6 16 + #define LCD_PINS_D7 17 #else - #define LCD_PINS_RS 4 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 29 - #define LCD_PINS_D6 28 - #define LCD_PINS_D7 27 + #define LCD_PINS_RS 4 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 30 + #define LCD_PINS_D5 29 + #define LCD_PINS_D6 28 + #define LCD_PINS_D7 27 #endif #if ENABLED(LCD_FOR_MELZI) - #define BTN_ENC 28 - #define BTN_EN1 29 - #define BTN_EN2 30 + #define BTN_ENC 28 + #define BTN_EN1 29 + #define BTN_EN2 30 - #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards + #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define ADC_KEYPAD_PIN 1 - #define BTN_EN1 -1 - #define BTN_EN2 -1 + #define ADC_KEYPAD_PIN 1 + #define BTN_EN1 -1 + #define BTN_EN2 -1 #elif ENABLED(LCD_I2C_PANELOLU2) #if IS_MELZI - #define BTN_ENC 29 - #define LCD_SDSS 30 // Panelolu2 SD card reader rather than the Melzi + #define BTN_ENC 29 + #define LCD_SDSS 30 // Panelolu2 SD card reader rather than the Melzi #else - #define BTN_ENC 30 + #define BTN_ENC 30 #endif - #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 + #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 - #define BTN_ENC 16 - #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi + #define BTN_ENC 16 + #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi #endif #if ENABLED(NEWPANEL) && !defined(BTN_EN1) - #define BTN_EN1 11 - #define BTN_EN2 10 + #define BTN_EN1 11 + #define BTN_EN2 10 #endif #endif // HAS_SPI_LCD @@ -277,13 +277,13 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL) // try to use IO Header + #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(ULTRA_LCD, NEWPANEL)// try to use IO Header - #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_DIR_PIN 11 + #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM + #define SPINDLE_DIR_PIN 11 - #elif !MB(MELZI) // use X stepper motor socket + #elif !MB(MELZI) // use X stepper motor socket /** * To control the spindle speed and have an LCD you must sacrifice @@ -315,11 +315,11 @@ #undef X_DIR_PIN #undef X_ENABLE_PIN #undef X_STEP_PIN - #define X_DIR_PIN 0 - #define X_ENABLE_PIN 14 - #define X_STEP_PIN 1 - #define SPINDLE_LASER_PWM_PIN 15 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 21 // Pullup! - #define SPINDLE_DIR_PIN -1 // No pin available on the socket for the direction pin + #define X_DIR_PIN 0 + #define X_ENABLE_PIN 14 + #define X_STEP_PIN 1 + #define SPINDLE_LASER_PWM_PIN 15 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 21 // Pullup! + #define SPINDLE_DIR_PIN -1 // No pin available on the socket for the direction pin #endif #endif diff --git a/Marlin/src/pins/sanguino/pins_SETHI.h b/Marlin/src/pins/sanguino/pins_SETHI.h index 528ec4455f..b945869cbc 100644 --- a/Marlin/src/pins/sanguino/pins_SETHI.h +++ b/Marlin/src/pins/sanguino/pins_SETHI.h @@ -57,69 +57,69 @@ #define BOARD_INFO_NAME "Sethi 3D_1" #ifndef GEN7_VERSION - #define GEN7_VERSION 12 // v1.x + #define GEN7_VERSION 12 // v1.x #endif // // Limit Switches // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 0 -#define Z_MIN_PIN 1 -#define Z_MAX_PIN 0 +#define X_STOP_PIN 2 +#define Y_STOP_PIN 0 +#define Z_MIN_PIN 1 +#define Z_MAX_PIN 0 // // Steppers // -#define X_STEP_PIN 19 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN 19 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 24 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN 26 +#define Z_DIR_PIN 25 +#define Z_ENABLE_PIN 24 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 24 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 #ifndef FAN_PIN #if GEN7_VERSION >= 13 // Gen7 v1.3 removed the fan pin - #define FAN_PIN -1 + #define FAN_PIN -1 #else - #define FAN_PIN 31 + #define FAN_PIN 31 #endif #endif // // Misc. Functions // -#define PS_ON_PIN 15 +#define PS_ON_PIN 15 // All these generations of Gen7 supply thermistor power // via PS_ON, so ignore bad thermistor readings -//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // our pin for debugging. -#define DEBUG_PIN 0 +#define DEBUG_PIN 0 // our RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index fa555f4151..fef8eeb617 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -42,56 +42,56 @@ // // Servos // -#define SERVO0_PIN PA1 // SERVOS +#define SERVO0_PIN PA1 // SERVOS // // Limit Switches // -#define X_STOP_PIN PC1 // X-STOP -#define Y_STOP_PIN PC0 // Y-STOP -#define Z_STOP_PIN PC15 // Z-STOP +#define X_STOP_PIN PC1 // X-STOP +#define Y_STOP_PIN PC0 // Y-STOP +#define Z_STOP_PIN PC15 // Z-STOP // // Z Probe must be this pin // -#define Z_MIN_PROBE_PIN PC14 // PROBE +#define Z_MIN_PROBE_PIN PC14 // PROBE // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PC2 // E0-STOP + #define FIL_RUNOUT_PIN PC2 // E0-STOP #endif // // Steppers // -#define X_ENABLE_PIN PC7 -#define X_STEP_PIN PC6 -#define X_DIR_PIN PB15 +#define X_ENABLE_PIN PC7 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PB15 #ifndef X_CS_PIN - #define X_CS_PIN PC10 + #define X_CS_PIN PC10 #endif -#define Y_ENABLE_PIN PB14 -#define Y_STEP_PIN PB13 -#define Y_DIR_PIN PB12 +#define Y_ENABLE_PIN PB14 +#define Y_STEP_PIN PB13 +#define Y_DIR_PIN PB12 #ifndef Y_CS_PIN - #define Y_CS_PIN PC11 + #define Y_CS_PIN PC11 #endif -#define Z_ENABLE_PIN PB11 -#define Z_STEP_PIN PB10 -#define Z_DIR_PIN PB2 +#define Z_ENABLE_PIN PB11 +#define Z_STEP_PIN PB10 +#define Z_DIR_PIN PB2 #ifndef Z_CS_PIN - #define Z_CS_PIN PC12 + #define Z_CS_PIN PC12 #endif -#define E0_ENABLE_PIN PB1 -#define E0_STEP_PIN PB0 -#define E0_DIR_PIN PC5 +#define E0_ENABLE_PIN PB1 +#define E0_STEP_PIN PB0 +#define E0_DIR_PIN PC5 #ifndef E0_CS_PIN - #define E0_CS_PIN PD2 + #define E0_CS_PIN PD2 #endif // @@ -99,13 +99,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 + #define TMC_SW_MOSI PB5 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 + #define TMC_SW_MISO PB4 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 + #define TMC_SW_SCK PB3 #endif #endif @@ -124,17 +124,17 @@ // // Software serial // - #define X_SERIAL_TX_PIN PC10 - #define X_SERIAL_RX_PIN PC10 + #define X_SERIAL_TX_PIN PC10 + #define X_SERIAL_RX_PIN PC10 - #define Y_SERIAL_TX_PIN PC11 - #define Y_SERIAL_RX_PIN PC11 + #define Y_SERIAL_TX_PIN PC11 + #define Y_SERIAL_RX_PIN PC11 - #define Z_SERIAL_TX_PIN PC12 - #define Z_SERIAL_RX_PIN PC12 + #define Z_SERIAL_TX_PIN PC12 + #define Z_SERIAL_RX_PIN PC12 - #define E0_SERIAL_TX_PIN PD2 - #define E0_SERIAL_RX_PIN PD2 + #define E0_SERIAL_TX_PIN PD2 + #define E0_SERIAL_RX_PIN PD2 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -143,23 +143,23 @@ // // Temperature Sensors // -#define TEMP_0_PIN PA0 // Analog Input "TH0" -#define TEMP_BED_PIN PC3 // Analog Input "TB0" +#define TEMP_0_PIN PA0 // Analog Input "TH0" +#define TEMP_BED_PIN PC3 // Analog Input "TB0" // // Heaters / Fans // -#define HEATER_0_PIN PC8 // HE -#define HEATER_BED_PIN PC9 // HB -#define FAN_PIN PA8 // FAN0 +#define HEATER_0_PIN PC8 // HE +#define HEATER_BED_PIN PC9 // HB +#define FAN_PIN PA8 // FAN0 // // USB connect control // -#define USB_CONNECT_PIN PC13 +#define USB_CONNECT_PIN PC13 #define USB_CONNECT_INVERTING false -#define SD_DETECT_PIN PC4 +#define SD_DETECT_PIN PC4 /** * _____ @@ -172,27 +172,27 @@ * EXP1 */ -#define EXPA1_03_PIN PB7 -#define EXPA1_04_PIN PB8 -#define EXPA1_05_PIN PB9 -#define EXPA1_06_PIN PA10 -#define EXPA1_07_PIN -1 -#define EXPA1_08_PIN PA9 -#define EXPA1_09_PIN PB6 -#define EXPA1_10_PIN PA15 +#define EXPA1_03_PIN PB7 +#define EXPA1_04_PIN PB8 +#define EXPA1_05_PIN PB9 +#define EXPA1_06_PIN PA10 +#define EXPA1_07_PIN -1 +#define EXPA1_08_PIN PA9 +#define EXPA1_09_PIN PB6 +#define EXPA1_10_PIN PA15 #if HAS_SPI_LCD - #define BTN_ENC EXPA1_09_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN EXPA1_10_PIN - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_ENABLE EXPA1_03_PIN + #define LCD_PINS_D4 EXPA1_05_PIN #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) @@ -207,12 +207,12 @@ * EXP1 */ - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_CS EXPA1_04_PIN + #define DOGLCD_A0 EXPA1_05_PIN + #define DOGLCD_SCK EXPA1_10_PIN + #define DOGLCD_MOSI EXPA1_03_PIN #define FORCE_SOFT_SPI - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #else #error "Only CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY, and MKS_MINI_12864 are currently supported on the BIGTREE_SKR_E3_DIP." @@ -226,8 +226,8 @@ #define HAS_ONBOARD_SD #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ON_BOARD_SPI_DEVICE 1 //SPI1 -#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#define ON_BOARD_SPI_DEVICE 1 //SPI1 +#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 77a412ad61..15bc01263a 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -40,66 +40,66 @@ // // Servos // -#define SERVO0_PIN PA1 +#define SERVO0_PIN PA1 // // Limit Switches // -#define X_STOP_PIN PC0 -#define Y_STOP_PIN PC1 -#define Z_STOP_PIN PC2 +#define X_STOP_PIN PC0 +#define Y_STOP_PIN PC1 +#define Z_STOP_PIN PC2 // // Z Probe must be this pins // -#define Z_MIN_PROBE_PIN PC14 +#define Z_MIN_PROBE_PIN PC14 // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PC15 // "E0-STOP" + #define FIL_RUNOUT_PIN PC15 // "E0-STOP" #endif // // Steppers // -#define X_ENABLE_PIN PB14 -#define X_STEP_PIN PB13 -#define X_DIR_PIN PB12 +#define X_ENABLE_PIN PB14 +#define X_STEP_PIN PB13 +#define X_DIR_PIN PB12 -#define Y_ENABLE_PIN PB11 -#define Y_STEP_PIN PB10 -#define Y_DIR_PIN PB2 +#define Y_ENABLE_PIN PB11 +#define Y_STEP_PIN PB10 +#define Y_DIR_PIN PB2 -#define Z_ENABLE_PIN PB1 -#define Z_STEP_PIN PB0 -#define Z_DIR_PIN PC5 +#define Z_ENABLE_PIN PB1 +#define Z_STEP_PIN PB0 +#define Z_DIR_PIN PC5 -#define E0_ENABLE_PIN PD2 -#define E0_STEP_PIN PB3 -#define E0_DIR_PIN PB4 +#define E0_ENABLE_PIN PD2 +#define E0_STEP_PIN PB3 +#define E0_DIR_PIN PB4 // // Temperature Sensors // -#define TEMP_0_PIN PA0 // Analog Input -#define TEMP_BED_PIN PC3 // Analog Input +#define TEMP_0_PIN PA0 // Analog Input +#define TEMP_BED_PIN PC3 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PC8 // EXTRUDER -#define HEATER_BED_PIN PC9 // BED -#define FAN_PIN PA8 +#define HEATER_0_PIN PC8 // EXTRUDER +#define HEATER_BED_PIN PC9 // BED +#define FAN_PIN PA8 // // USB connect control // -#define USB_CONNECT_PIN PC13 +#define USB_CONNECT_PIN PC13 #define USB_CONNECT_INVERTING false -#define SD_DETECT_PIN PC4 +#define SD_DETECT_PIN PC4 /** * _____ @@ -112,40 +112,40 @@ * EXP1 */ -#define EXPA1_03_PIN PB7 -#define EXPA1_04_PIN PB8 -#define EXPA1_05_PIN PB9 -#define EXPA1_06_PIN PA10 -#define EXPA1_07_PIN -1 -#define EXPA1_08_PIN PA9 -#define EXPA1_09_PIN PB6 -#define EXPA1_10_PIN PB5 +#define EXPA1_03_PIN PB7 +#define EXPA1_04_PIN PB8 +#define EXPA1_05_PIN PB9 +#define EXPA1_06_PIN PA10 +#define EXPA1_07_PIN -1 +#define EXPA1_08_PIN PA9 +#define EXPA1_09_PIN PB6 +#define EXPA1_10_PIN PB5 #if HAS_SPI_LCD #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN EXPA1_10_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_ENABLE EXPA1_03_PIN + #define LCD_PINS_D4 EXPA1_05_PIN - #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." - #define LCD_PINS_RS EXPA1_05_PIN - #define LCD_PINS_ENABLE EXPA1_09_PIN - #define LCD_PINS_D4 EXPA1_04_PIN - #define LCD_PINS_D5 EXPA1_06_PIN - #define LCD_PINS_D6 EXPA1_08_PIN - #define LCD_PINS_D7 EXPA1_10_PIN - #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! + #define LCD_PINS_RS EXPA1_05_PIN + #define LCD_PINS_ENABLE EXPA1_09_PIN + #define LCD_PINS_D4 EXPA1_04_PIN + #define LCD_PINS_D5 EXPA1_06_PIN + #define LCD_PINS_D6 EXPA1_08_PIN + #define LCD_PINS_D7 EXPA1_10_PIN + #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) @@ -159,16 +159,16 @@ * ----- * EXP1 */ - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_CS EXPA1_04_PIN + #define DOGLCD_A0 EXPA1_05_PIN + #define DOGLCD_SCK EXPA1_10_PIN + #define DOGLCD_MOSI EXPA1_03_PIN #define FORCE_SOFT_SPI - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #else @@ -184,8 +184,8 @@ #define HAS_ONBOARD_SD #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif -#define ON_BOARD_SPI_DEVICE 1 // SPI1 -#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#define ON_BOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h index 8935da85af..961620ee8b 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h @@ -25,7 +25,7 @@ #define BOARD_INFO_NAME "BIGTREE SKR Mini E3 V1.2" -#define NEOPIXEL_PIN PC7 // LED driving pin +#define NEOPIXEL_PIN PC7 // LED driving pin /** * TMC2208/TMC2209 stepper drivers @@ -34,17 +34,17 @@ // // Software serial // - #define X_SERIAL_TX_PIN PB15 - #define X_SERIAL_RX_PIN PB15 + #define X_SERIAL_TX_PIN PB15 + #define X_SERIAL_RX_PIN PB15 - #define Y_SERIAL_TX_PIN PC6 - #define Y_SERIAL_RX_PIN PC6 + #define Y_SERIAL_TX_PIN PC6 + #define Y_SERIAL_RX_PIN PC6 - #define Z_SERIAL_TX_PIN PC10 - #define Z_SERIAL_RX_PIN PC10 + #define Z_SERIAL_TX_PIN PC10 + #define Z_SERIAL_RX_PIN PC10 - #define E0_SERIAL_TX_PIN PC11 - #define E0_SERIAL_RX_PIN PC11 + #define E0_SERIAL_TX_PIN PC11 + #define E0_SERIAL_RX_PIN PC11 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 08f666882e..fff3af5b6b 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -41,57 +41,57 @@ // // Limit Switches // -#define X_MIN_PIN PC2 -#define X_MAX_PIN PA2 -#define Y_MIN_PIN PC1 -#define Y_MAX_PIN PA1 -#define Z_MIN_PIN PC0 -#define Z_MAX_PIN PC3 +#define X_MIN_PIN PC2 +#define X_MAX_PIN PA2 +#define Y_MIN_PIN PC1 +#define Y_MAX_PIN PA1 +#define Z_MIN_PIN PC0 +#define Z_MAX_PIN PC3 // // Steppers // -#define X_STEP_PIN PC6 -#define X_DIR_PIN PC7 -#define X_ENABLE_PIN PB15 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PC7 +#define X_ENABLE_PIN PB15 -#define Y_STEP_PIN PB13 -#define Y_DIR_PIN PB14 -#define Y_ENABLE_PIN PB12 +#define Y_STEP_PIN PB13 +#define Y_DIR_PIN PB14 +#define Y_ENABLE_PIN PB12 -#define Z_STEP_PIN PB10 -#define Z_DIR_PIN PB11 -#define Z_ENABLE_PIN PB2 +#define Z_STEP_PIN PB10 +#define Z_DIR_PIN PB11 +#define Z_ENABLE_PIN PB2 -#define E0_STEP_PIN PC5 -#define E0_DIR_PIN PB0 -#define E0_ENABLE_PIN PC4 +#define E0_STEP_PIN PC5 +#define E0_DIR_PIN PB0 +#define E0_ENABLE_PIN PC4 #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 + #define TMC_SW_SCK PB3 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 + #define TMC_SW_MISO PB4 #endif #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 + #define TMC_SW_MOSI PB5 #endif #endif // // Heaters / Fans // -#define HEATER_0_PIN PA8 -#define FAN_PIN PC8 -#define HEATER_BED_PIN PC9 +#define HEATER_0_PIN PA8 +#define FAN_PIN PC8 +#define HEATER_BED_PIN PC9 // // Temperature Sensors // -#define TEMP_BED_PIN PB1 // Analog Input -#define TEMP_0_PIN PA0 // Analog Input +#define TEMP_BED_PIN PB1 // Analog Input +#define TEMP_0_PIN PA0 // Analog Input // // LCD Pins @@ -109,41 +109,41 @@ */ #if HAS_SPI_LCD - #define BEEPER_PIN PC10 - #define BTN_ENC PC11 + #define BEEPER_PIN PC10 + #define BTN_ENC PC11 #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PC15 + #define LCD_PINS_RS PC15 - #define BTN_EN1 PB6 - #define BTN_EN2 PC13 + #define BTN_EN1 PB6 + #define BTN_EN2 PC13 - #define LCD_PINS_ENABLE PC14 - #define LCD_PINS_D4 PB7 + #define LCD_PINS_ENABLE PC14 + #define LCD_PINS_D4 PB7 #else - #define LCD_PINS_RS PC12 + #define LCD_PINS_RS PC12 - #define BTN_EN1 PD2 - #define BTN_EN2 PB8 + #define BTN_EN1 PD2 + #define BTN_EN2 PB8 - #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_ENABLE PB6 #if ENABLED(FYSETC_MINI_12864) - #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PC13 - #define DOGLCD_A0 PC12 - #define DOGLCD_CS PB6 - #define DOGLCD_SCK PB3 - #define DOGLCD_MOSI PB5 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PC13 + #define DOGLCD_A0 PC12 + #define DOGLCD_CS PB6 + #define DOGLCD_SCK PB3 + #define DOGLCD_MOSI PB5 - #define FORCE_SOFT_SPI // SPI MODE3 + #define FORCE_SOFT_SPI // SPI MODE3 - #define LED_PIN PB7 // red pwm - //#define LED_PIN PC15 // green - //#define LED_PIN PC14 // blue + #define LED_PIN PB7 // red pwm + //#define LED_PIN PC15 // green + //#define LED_PIN PC14 // blue //#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) // #ifndef RGB_LED_R_PIN @@ -159,13 +159,13 @@ // #define NEOPIXEL_PIN PB7 //#endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 - #define LCD_PINS_D4 PC13 + #define LCD_PINS_D4 PC13 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PB7 - #define LCD_PINS_D6 PC15 - #define LCD_PINS_D7 PC14 + #define LCD_PINS_D5 PB7 + #define LCD_PINS_D6 PC15 + #define LCD_PINS_D7 PC14 #endif #endif // !FYSETC_MINI_12864 @@ -182,26 +182,26 @@ // set SDCARD_CONNECTION form 'ONBOARD' to 'LCD' and use an external SD (connected to LCD) #define HAS_ONBOARD_SD #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(LCD) #define ENABLE_SPI3 - #define SD_DETECT_PIN PB9 - #define SCK_PIN PB3 - #define MISO_PIN PB4 - #define MOSI_PIN PB5 - #define SS_PIN PA15 + #define SD_DETECT_PIN PB9 + #define SCK_PIN PB3 + #define MISO_PIN PB4 + #define MOSI_PIN PB5 + #define SS_PIN PA15 #elif SD_CONNECTION_IS(ONBOARD) #define ENABLE_SPI1 - #define SD_DETECT_PIN PA3 - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PA7 - #define SS_PIN PA4 + #define SD_DETECT_PIN PA3 + #define SCK_PIN PA5 + #define MISO_PIN PA6 + #define MOSI_PIN PA7 + #define SS_PIN PA4 #endif -#define ON_BOARD_SPI_DEVICE 1 //SPI1 -#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#define ON_BOARD_SPI_DEVICE 1 //SPI1 +#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card #if HAS_GRAPHICAL_LCD #define BOARD_ST7920_DELAY_1 DELAY_NS(125) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index 2db6b1bc0b..b9272c7211 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -41,69 +41,67 @@ // // Steppers // -#define X_STEP_PIN PE5 -#define X_DIR_PIN PE6 -#define X_ENABLE_PIN PC13 -#define X_MIN_PIN PG10 -#define X_MAX_PIN -1 +#define X_STEP_PIN PE5 +#define X_DIR_PIN PE6 +#define X_ENABLE_PIN PC13 +#define X_MIN_PIN PG10 +#define X_MAX_PIN -1 -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 -#define Y_ENABLE_PIN PE4 -#define Y_MIN_PIN PA12 +#define Y_STEP_PIN PE2 +#define Y_DIR_PIN PE3 +#define Y_ENABLE_PIN PE4 +#define Y_MIN_PIN PA12 #define Y_MAX_PIN -#define Z_STEP_PIN PB9 -#define Z_DIR_PIN PE0 -#define Z_ENABLE_PIN PE1 -#define Z_MIN_PIN PA14 -#define Z_MAX_PIN -1 +#define Z_STEP_PIN PB9 +#define Z_DIR_PIN PE0 +#define Z_ENABLE_PIN PE1 +#define Z_MIN_PIN PA14 +#define Z_MAX_PIN -1 -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 +#define Y2_STEP_PIN -1 +#define Y2_DIR_PIN -1 +#define Y2_ENABLE_PIN -1 -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 +#define Z2_STEP_PIN -1 +#define Z2_DIR_PIN -1 +#define Z2_ENABLE_PIN -1 -#define E0_STEP_PIN PB4 -#define E0_DIR_PIN PB5 -#define E0_ENABLE_PIN PB8 +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB5 +#define E0_ENABLE_PIN PB8 +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 - -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 - -#define E2_STEP_PIN -1 -#define E2_DIR_PIN -1 -#define E2_ENABLE_PIN -1 +#define E2_STEP_PIN -1 +#define E2_DIR_PIN -1 +#define E2_ENABLE_PIN -1 // // Misc. Functions // -#define SDSS -1 -#define LED_PIN -1 -#define CASE_LIGHT_PIN PA8 // 8 +#define SDSS -1 +#define LED_PIN -1 +#define CASE_LIGHT_PIN PA8 // 8 -#define PS_ON_PIN -1 -#define KILL_PIN PD6 // LED strip 24v +#define PS_ON_PIN -1 +#define KILL_PIN PD6 // LED strip 24v // // Heaters / Fans // -#define HEATER_0_PIN PD12 // HOT-END -#define HEATER_1_PIN -1 -#define HEATER_2_PIN -1 +#define HEATER_0_PIN PD12 // HOT-END +#define HEATER_1_PIN -1 +#define HEATER_2_PIN -1 -#define HEATER_BED_PIN PG11 // HOT-BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 +#define HEATER_BED_PIN PG11 // HOT-BED +#define HEATER_BED2_PIN -1 // BED2 +#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN - #define FAN_PIN PG14 // MAIN BOARD FAN + #define FAN_PIN PG14 // MAIN BOARD FAN #endif #define FAN_SOFT_PWM @@ -111,10 +109,10 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA0 // Analog Input -#define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_2_PIN -1 // Analog Input +#define TEMP_BED_PIN PA0 // Analog Input +#define TEMP_0_PIN PA1 // Analog Input +#define TEMP_1_PIN -1 // Analog Input +#define TEMP_2_PIN -1 // Analog Input // // LCD Pins @@ -122,31 +120,31 @@ #if HAS_SPI_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PD3 // 51 // SID (MOSI) - #define LCD_PINS_D4 PD4 // 52 // SCK (CLK) clock + #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PD3 // 51 // SID (MOSI) + #define LCD_PINS_D4 PD4 // 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #else - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #if DISABLED(NEWPANEL) - #define BEEPER_PIN PC1 // 33 + #define BEEPER_PIN PC1 // 33 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK PC6 // 38 - //#define SHIFT_LD PC10 // 42 - //#define SHIFT_OUT PC8 // 40 - //#define SHIFT_EN PA1 // 17 + //#define SHIFT_CLK PC6 // 38 + //#define SHIFT_LD PC10 // 42 + //#define SHIFT_OUT PC8 // 40 + //#define SHIFT_EN PA1 // 17 #endif #endif @@ -154,127 +152,127 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN PC5 + #define BEEPER_PIN PC5 - #define BTN_EN1 PB15 // 31 - #define BTN_EN2 PC1 // 33 - #define BTN_ENC PC3 // 35 + #define BTN_EN1 PB15 // 31 + #define BTN_EN2 PC1 // 33 + #define BTN_ENC PC3 // 35 - #define SD_DETECT_PIN PD1 // 49 - #define KILL_PIN PC9 // 41 + #define SD_DETECT_PIN PD1 // 49 + #define KILL_PIN PC9 // 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN PC7 // 39 + #define LCD_BACKLIGHT_PIN PC7 // 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 PE0 // 64 - #define BTN_EN2 PD11 // 59 - #define BTN_ENC PD15 // 63 - #define SD_DETECT_PIN PC10 // 42 + #define BTN_EN1 PE0 // 64 + #define BTN_EN2 PD11 // 59 + #define BTN_ENC PD15 // 63 + #define SD_DETECT_PIN PC10 // 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 PC15 // 47 - #define BTN_EN2 PC11 // 43 - #define BTN_ENC PC0 // 32 - #define LCD_SDSS PD5 // 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN PC9 // 41 + #define BTN_EN1 PC15 // 47 + #define BTN_EN2 PC11 // 43 + #define BTN_ENC PC0 // 32 + #define LCD_SDSS PD5 // 53 + #define SD_DETECT_PIN -1 + #define KILL_PIN PC9 // 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 PB6 // 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 PA7 // 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 PB6 // 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 PA7 // 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 - #define LCD_SDSS PD5 // 53 - #define SD_DETECT_PIN PD1 // 49 + #define BTN_ENC -1 + #define LCD_SDSS PD5 // 53 + #define SD_DETECT_PIN PD1 // 49 #elif ANY(VIKI2, miniVIKI) - #define BEEPER_PIN PC1 // 33 + #define BEEPER_PIN PC1 // 33 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 PC12 // 44 - #define DOGLCD_CS PC13 // 45 + #define DOGLCD_A0 PC12 // 44 + #define DOGLCD_CS PC13 // 45 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 PB6 // 22 - #define BTN_EN2 PA7 // 7 - #define BTN_ENC PC7 // 39 + #define BTN_EN1 PB6 // 22 + #define BTN_EN2 PA7 // 7 + #define BTN_ENC PC7 // 39 - #define SDSS PD5 // 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board + #define SDSS PD5 // 53 + #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN PB15 // 31 + #define KILL_PIN PB15 // 31 - #define STAT_LED_RED_PIN PC0 // 32 - #define STAT_LED_BLUE_PIN PC3 // 35 + #define STAT_LED_RED_PIN PC0 // 32 + #define STAT_LED_BLUE_PIN PC3 // 35 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 PC3 // 35 - #define BTN_EN2 PC5 // 37 - #define BTN_ENC PB15 // 31 - #define SD_DETECT_PIN PD1 // 49 - #define LCD_SDSS PD5 // 53 - #define KILL_PIN PC9 // 41 - #define BEEPER_PIN PB7 // 23 - #define DOGLCD_CS PB13 // 29 - #define DOGLCD_A0 PB11 // 27 - #define LCD_BACKLIGHT_PIN PC1 // 33 + #define BTN_EN1 PC3 // 35 + #define BTN_EN2 PC5 // 37 + #define BTN_ENC PB15 // 31 + #define SD_DETECT_PIN PD1 // 49 + #define LCD_SDSS PD5 // 53 + #define KILL_PIN PC9 // 41 + #define BEEPER_PIN PB7 // 23 + #define DOGLCD_CS PB13 // 29 + #define DOGLCD_A0 PB11 // 27 + #define LCD_BACKLIGHT_PIN PC1 // 33 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN PC10 // 42 + #define BEEPER_PIN PC10 // 42 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 PC12 // 44 - #define DOGLCD_CS PE2 // 66 - #define LCD_BACKLIGHT_PIN PE1 // 65 // backlight LED on A11/D65 - #define SDSS PD5 // 53 + #define DOGLCD_A0 PC12 // 44 + #define DOGLCD_CS PE2 // 66 + #define LCD_BACKLIGHT_PIN PE1 // 65 // backlight LED on A11/D65 + #define SDSS PD5 // 53 - #define KILL_PIN PE0 // 64 + #define KILL_PIN PE0 // 64 // GLCD features // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 // The encoder and click button - #define BTN_EN1 PC8 // 40 - #define BTN_EN2 PD15 // 63 - #define BTN_ENC PD11 // 59 + #define BTN_EN1 PC8 // 40 + #define BTN_EN2 PD15 // 63 + #define BTN_ENC PD11 // 59 // not connected to a pin - #define SD_DETECT_PIN PD1 // 49 + #define SD_DETECT_PIN PD1 // 49 #else // Beeper on AUX-4 - #define BEEPER_PIN PC1 // 33 + #define BEEPER_PIN PC1 // 33 // Buttons directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 PE0 // 64 - #define BTN_EN2 PD11 // 59 - #define BTN_ENC PD15 // 63 - #define SHIFT_OUT PC8 // 40 - #define SHIFT_CLK PC12 // 44 - #define SHIFT_LD PC10 // 42 + #define BTN_EN1 PE0 // 64 + #define BTN_EN2 PD11 // 59 + #define BTN_ENC PD15 // 63 + #define SHIFT_OUT PC8 // 40 + #define SHIFT_CLK PC12 // 44 + #define SHIFT_LD PC10 // 42 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 PD11 // 59 // AUX2 PIN 3 - #define BTN_EN2 PD15 // 63 // AUX2 PIN 4 - #define BTN_ENC PD1 // 49 // AUX3 PIN 7 + #define BTN_EN1 PD11 // 59 // AUX2 PIN 3 + #define BTN_EN2 PD15 // 63 // AUX2 PIN 4 + #define BTN_ENC PD1 // 49 // AUX3 PIN 7 #else - #define BTN_EN1 PC5 // 37 - #define BTN_EN2 PC3 // 35 - #define BTN_ENC PB15 // 31 + #define BTN_EN1 PC5 // 37 + #define BTN_EN2 PC3 // 35 + #define BTN_ENC PB15 // 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN PD1 // 49 - #define KILL_PIN PC9 // 41 + #define SD_DETECT_PIN PD1 // 49 + #define KILL_PIN PC9 // 41 #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this + //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index db76042ab7..dcd1119c86 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -46,55 +46,55 @@ // // Limit Switches // -#define X_STOP_PIN PA1 -#define Y_STOP_PIN PA0 -#define Z_STOP_PIN PB14 +#define X_STOP_PIN PA1 +#define Y_STOP_PIN PA0 +#define Z_STOP_PIN PB14 // // Filament runout // #ifdef pins_v2_20190128 - #define FIL_RUNOUT_PIN PB15 + #define FIL_RUNOUT_PIN PB15 #else - #define FIL_RUNOUT_PIN PB5 + #define FIL_RUNOUT_PIN PB5 #endif // // Steppers // -#define X_STEP_PIN PB8 -#define X_DIR_PIN PB9 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PB8 +#define X_DIR_PIN PB9 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PB2 +#define Y_STEP_PIN PB2 #ifdef pins_v2_20190128 - #define Y_DIR_PIN PB3 + #define Y_DIR_PIN PB3 #else - #define Y_DIR_PIN PB0 + #define Y_DIR_PIN PB0 #endif -#define Y_ENABLE_PIN PB1 +#define Y_ENABLE_PIN PB1 -#define Z_STEP_PIN PC0 -#define Z_DIR_PIN PC1 -#define Z_ENABLE_PIN PC2 +#define Z_STEP_PIN PC0 +#define Z_DIR_PIN PC1 +#define Z_ENABLE_PIN PC2 -#define E0_STEP_PIN PC15 -#define E0_DIR_PIN PC14 -#define E0_ENABLE_PIN PC13 +#define E0_STEP_PIN PC15 +#define E0_DIR_PIN PC14 +#define E0_ENABLE_PIN PC13 // // Stepper current PWM // // X:PA2 Y:PA3 Z:PB12 E:PB13 // changed for test -//#define MOTOR_CURRENT_PWM_XY_PIN PA3 -//#define MOTOR_CURRENT_PWM_Z_PIN PA2 // PB12 -//#define MOTOR_CURRENT_PWM_XY_PIN PB6 -//#define MOTOR_CURRENT_PWM_Z_PIN PB7 // PB12 -//#define MOTOR_CURRENT_PWM_E_PIN -1 // PB13 +//#define MOTOR_CURRENT_PWM_XY_PIN PA3 +//#define MOTOR_CURRENT_PWM_Z_PIN PA2 // PB12 +//#define MOTOR_CURRENT_PWM_XY_PIN PB6 +//#define MOTOR_CURRENT_PWM_Z_PIN PB7 // PB12 +//#define MOTOR_CURRENT_PWM_E_PIN -1 // PB13 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE - #define MOTOR_CURRENT_PWM_RANGE 1500 // geo-f:old 2000 + #define MOTOR_CURRENT_PWM_RANGE 1500 // geo-f:old 2000 #endif #define DEFAULT_PWM_MOTOR_CURRENT {500, 500, 400} // geo-f:old 1300 1300 1250 @@ -112,37 +112,37 @@ // // Heaters / Fans // -#define HEATER_0_PIN PC7 -#define HEATER_BED_PIN PC6 +#define HEATER_0_PIN PC7 +#define HEATER_BED_PIN PC6 #ifndef FAN_PIN - #define FAN_PIN PC8 + #define FAN_PIN PC8 #endif // // Temperature Sensors // -#define TEMP_BED_PIN PC5 // Analog Input -#define TEMP_0_PIN PC4 // Analog Input +#define TEMP_BED_PIN PC5 // Analog Input +#define TEMP_0_PIN PC4 // Analog Input // // Misc. Functions // -#define SDSS PA4 +#define SDSS PA4 // // LCD Pins // #if HAS_SPI_LCD - #define BEEPER_PIN PC9 + #define BEEPER_PIN PC9 #if HAS_GRAPHICAL_LCD - #define DOGLCD_A0 PA15 + #define DOGLCD_A0 PA15 #ifdef pins_v2_20190128 - #define DOGLCD_CS PB5 + #define DOGLCD_CS PB5 #else - #define DOGLCD_CS PB7 + #define DOGLCD_CS PB7 #endif //#define LCD_CONTRAST_INIT 190 @@ -153,36 +153,36 @@ #endif // not connected to a pin - #define SD_DETECT_PIN PC3 + #define SD_DETECT_PIN PC3 #if ENABLED(NEWPANEL) // The encoder and click button - #define BTN_EN1 PC10 - #define BTN_EN2 PC11 - #define BTN_ENC PC12 + #define BTN_EN1 PC10 + #define BTN_EN2 PC11 + #define BTN_ENC PC12 #endif #ifdef pins_v2_20190128 - #define LCD_RESET_PIN PB4 + #define LCD_RESET_PIN PB4 #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB0 + #define RGB_LED_R_PIN PB0 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB6 + #define RGB_LED_G_PIN PB6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB7 + #define RGB_LED_B_PIN PB7 #endif #else - #define LCD_RESET_PIN PB6 + #define LCD_RESET_PIN PB6 #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB3 + #define RGB_LED_R_PIN PB3 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB4 + #define RGB_LED_G_PIN PB4 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB5 + #define RGB_LED_B_PIN PB5 #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index a845ed161b..e726ca1831 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -44,38 +44,38 @@ // // Servos // -#define SERVO0_PIN PA0 +#define SERVO0_PIN PA0 // // Limit Switches // -#define X_STOP_PIN PA1 -#define Y_STOP_PIN PB4 -#define Z_STOP_PIN PA15 +#define X_STOP_PIN PA1 +#define Y_STOP_PIN PB4 +#define Z_STOP_PIN PA15 // // Filament runout // -#define FIL_RUNOUT_PIN PB5 +#define FIL_RUNOUT_PIN PB5 // // Steppers // -#define X_STEP_PIN PB8 -#define X_DIR_PIN PB9 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PB8 +#define X_DIR_PIN PB9 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PB2 -#define Y_DIR_PIN PB3 -#define Y_ENABLE_PIN PB1 +#define Y_STEP_PIN PB2 +#define Y_DIR_PIN PB3 +#define Y_ENABLE_PIN PB1 -#define Z_STEP_PIN PC0 -#define Z_DIR_PIN PC1 -#define Z_ENABLE_PIN PC2 +#define Z_STEP_PIN PC0 +#define Z_DIR_PIN PC1 +#define Z_ENABLE_PIN PC2 -#define E0_STEP_PIN PC15 -#define E0_DIR_PIN PC14 -#define E0_ENABLE_PIN PC13 +#define E0_STEP_PIN PC15 +#define E0_DIR_PIN PC14 +#define E0_ENABLE_PIN PC13 #define X_HARDWARE_SERIAL MSerial2 #define Y_HARDWARE_SERIAL MSerial2 @@ -85,35 +85,35 @@ // // Heaters / Fans // -#define HEATER_0_PIN PC6 -#define HEATER_BED_PIN PC7 +#define HEATER_0_PIN PC6 +#define HEATER_BED_PIN PC7 #ifndef FAN_PIN - #define FAN_PIN PC8 + #define FAN_PIN PC8 #endif // // Temperature Sensors // -#define TEMP_BED_PIN PC5 // Analog Input -#define TEMP_0_PIN PC4 // Analog Input +#define TEMP_BED_PIN PC5 // Analog Input +#define TEMP_0_PIN PC4 // Analog Input // // Misc. Functions // -#define SDSS PA4 +#define SDSS PA4 // // LCD Pins // #if HAS_SPI_LCD - #define BEEPER_PIN PC9 + #define BEEPER_PIN PC9 #if HAS_GRAPHICAL_LCD - #define DOGLCD_A0 PB14 - #define DOGLCD_CS PB12 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define DOGLCD_A0 PB14 + #define DOGLCD_CS PB12 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 @@ -123,29 +123,29 @@ #endif #endif - #define LCD_PINS_RS PB12 // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 PB13 // SCLK - #define LCD_PINS_ENABLE PB15 // DATA MOSI + #define LCD_PINS_RS PB12 // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 PB13 // SCLK + #define LCD_PINS_ENABLE PB15 // DATA MOSI // not connected to a pin - #define SD_DETECT_PIN PC3 + #define SD_DETECT_PIN PC3 #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB0 + #define RGB_LED_R_PIN PB0 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB7 + #define RGB_LED_G_PIN PB7 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB6 + #define RGB_LED_B_PIN PB6 #endif //#define LCD_CONTRAST_INIT 190 #if ENABLED(NEWPANEL) - #define BTN_EN1 PC11 - #define BTN_EN2 PC10 - #define BTN_ENC PC12 + #define BTN_EN1 PC11 + #define BTN_EN2 PC10 + #define BTN_ENC PC12 #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h index 3e283911b4..9c6412c0cb 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h @@ -36,7 +36,7 @@ #undef RGB_LED_G_PIN #undef RGB_LED_B_PIN -#define FAN1_PIN PB0 // Fan1 +#define FAN1_PIN PB0 // Fan1 #if HAS_TMC_UART @@ -47,17 +47,17 @@ // // Software serial // - #define X_SERIAL_TX_PIN PA11 - #define X_SERIAL_RX_PIN PA12 + #define X_SERIAL_TX_PIN PA11 + #define X_SERIAL_RX_PIN PA12 - #define Y_SERIAL_TX_PIN PB6 - #define Y_SERIAL_RX_PIN PB7 + #define Y_SERIAL_TX_PIN PB6 + #define Y_SERIAL_RX_PIN PB7 - #define Z_SERIAL_TX_PIN PB10 - #define Z_SERIAL_RX_PIN PB11 + #define Z_SERIAL_TX_PIN PB10 + #define Z_SERIAL_RX_PIN PB11 - #define E0_SERIAL_TX_PIN PA2 - #define E0_SERIAL_RX_PIN PA3 + #define E0_SERIAL_TX_PIN PA2 + #define E0_SERIAL_RX_PIN PA3 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index a35bd29888..38cc615f64 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -53,32 +53,32 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB // // Limit Switches // -#define X_MIN_PIN PE5 // ENDSTOPS 15,17 -#define X_MAX_PIN PE4 // ENDSTOPS 16,18 -#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 -#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 -#define Z_MIN_PIN PE1 // ENDSTOPS 3,5 -#define Z_MAX_PIN PE0 // ENDSTOPS 4,6 +#define X_MIN_PIN PE5 // ENDSTOPS 15,17 +#define X_MAX_PIN PE4 // ENDSTOPS 16,18 +#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 +#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 +#define Z_MIN_PIN PE1 // ENDSTOPS 3,5 +#define Z_MAX_PIN PE0 // ENDSTOPS 4,6 // // Steppers // -#define X_STEP_PIN PC6 -#define X_DIR_PIN PD13 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PD13 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PA12 -#define Y_DIR_PIN PA11 -#define Y_ENABLE_PIN PA15 +#define Y_STEP_PIN PA12 +#define Y_DIR_PIN PA11 +#define Y_ENABLE_PIN PA15 -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD3 -#define Z_ENABLE_PIN PB3 +#define Z_STEP_PIN PD6 +#define Z_DIR_PIN PD3 +#define Z_ENABLE_PIN PB3 // Extruder stepper pins // NOTE: Numbering here is made according to EXT connector numbers, @@ -86,46 +86,46 @@ // That is, E0_*_PIN are the E2_* lines connected to E2_A1 step // stick that drives the EXT0 output on the board. // -#define E0_STEP_PIN PC14 -#define E0_DIR_PIN PC13 -#define E0_ENABLE_PIN PC15 +#define E0_STEP_PIN PC14 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PC15 -#define E1_STEP_PIN PA0 -#define E1_DIR_PIN PB6 -#define E1_ENABLE_PIN PA1 +#define E1_STEP_PIN PA0 +#define E1_DIR_PIN PB6 +#define E1_ENABLE_PIN PA1 -#define E2_STEP_PIN PB2 -#define E2_DIR_PIN PB11 -#define E2_ENABLE_PIN PC4 +#define E2_STEP_PIN PB2 +#define E2_DIR_PIN PB11 +#define E2_ENABLE_PIN PC4 // // Heaters / Fans // -#define HEATER_0_PIN PB0 // EXT0 port -#define HEATER_1_PIN PB5 // EXT1 port -#define HEATER_2_PIN PB4 // EXT2 port -#define HEATER_BED_PIN PB1 // CON2X3 hotbed port +#define HEATER_0_PIN PB0 // EXT0 port +#define HEATER_1_PIN PB5 // EXT1 port +#define HEATER_2_PIN PB4 // EXT2 port +#define HEATER_BED_PIN PB1 // CON2X3 hotbed port // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan -#define FAN1_PIN PB8 // EXT1 port -#define FAN2_PIN PB7 // EXT2 port +//#define FAN_PIN PB9 // EXT0 port +#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#define FAN1_PIN PB8 // EXT1 port +#define FAN2_PIN PB7 // EXT2 port // // Temperature Sensors // -#define TEMP_0_PIN PC2 // EXT0 port -#define TEMP_1_PIN PC1 // EXT1 port -#define TEMP_2_PIN PC0 // EXT2 port -#define TEMP_BED_PIN PC3 // CON2X3 hotbed port +#define TEMP_0_PIN PC2 // EXT0 port +#define TEMP_1_PIN PC1 // EXT1 port +#define TEMP_2_PIN PC0 // EXT2 port +#define TEMP_BED_PIN PC3 // CON2X3 hotbed port // // Misc. Functions // -#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector +#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector // // LCD / Controller @@ -138,19 +138,19 @@ // Geeetech's LCD2004A Control Panel is very much like // RepRapDiscount Smart Controller, but adds an FFC40 connector // - #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) - #define LCD_PINS_D4 PD8 // SCK (CLK) clock - #define LCD_PINS_D5 PD9 - #define LCD_PINS_D6 PD10 - #define LCD_PINS_D7 PE15 + #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_D4 PD8 // SCK (CLK) clock + #define LCD_PINS_D5 PD9 + #define LCD_PINS_D6 PD10 + #define LCD_PINS_D7 PE15 #else // // Serial LCDs can be implemented in ExtUI // - //#define LCD_UART_TX PD8 - //#define LCD_UART_RX PD9 + //#define LCD_UART_TX PD8 + //#define LCD_UART_RX PD9 #endif #if HAS_GRAPHICAL_LCD @@ -167,9 +167,9 @@ // RepRapDiscount Smart Controller, but adds an FFC40 connector // connected with a flat wire to J2 connector on the board. // - #define BTN_EN1 PE8 - #define BTN_EN2 PE9 - #define BTN_ENC PE13 + #define BTN_EN1 PE8 + #define BTN_EN2 PE9 + #define BTN_ENC PE13 #define GTM32_PRO_VB_USE_LCD_BEEPER #define GTM32_PRO_VB_USE_EXT_SDCARD @@ -182,10 +182,10 @@ // This is pin 32 on J2 FFC40 and pin, goes to the beeper // on Geeetech's version of RepRapDiscount Smart Controller // (e.g. on Rostock 301) - #define BEEPER_PIN PE12 + #define BEEPER_PIN PE12 #else // This is the beeper on the board itself - #define BEEPER_PIN PB10 + #define BEEPER_PIN PB10 #endif /** @@ -203,28 +203,28 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PC11 - #define SCK_PIN PC12 - #define MOSI_PIN PD2 - #define MISO_PIN PC8 - #define SD_DETECT_PIN PC7 + #define SS_PIN PC11 + #define SCK_PIN PC12 + #define MOSI_PIN PD2 + #define MISO_PIN PC8 + #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 - #define SD_DETECT_PIN -1 // Card detect is not connected + #define SS_PIN PA4 + #define SCK_PIN PA5 + #define MOSI_PIN PA7 + #define MISO_PIN PA6 + #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. // Must define WIFISUPPORT in Configuration.h for the printer. // -#define ESP_WIFI_MODULE_COM 2 -#define ESP_WIFI_MODULE_BAUDRATE 115200 -#define ESP_WIFI_MODULE_RESET_PIN -1 +#define ESP_WIFI_MODULE_COM 2 +#define ESP_WIFI_MODULE_BAUDRATE 115200 +#define ESP_WIFI_MODULE_RESET_PIN -1 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 4c14165f79..873d02b065 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -53,32 +53,32 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB // // Limit Switches // -#define X_MIN_PIN PE5 // ENDSTOPS 15,17 -#define X_MAX_PIN PE4 // ENDSTOPS 16,18 -#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 -#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 -#define Z_MIN_PIN PE0 // ENDSTOPS 3,5 -#define Z_MAX_PIN PE1 // ENDSTOPS 4,6 +#define X_MIN_PIN PE5 // ENDSTOPS 15,17 +#define X_MAX_PIN PE4 // ENDSTOPS 16,18 +#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 +#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 +#define Z_MIN_PIN PE0 // ENDSTOPS 3,5 +#define Z_MAX_PIN PE1 // ENDSTOPS 4,6 // // Steppers // -#define X_STEP_PIN PC6 -#define X_DIR_PIN PD13 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PD13 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PA12 -#define Y_DIR_PIN PA11 -#define Y_ENABLE_PIN PA15 +#define Y_STEP_PIN PA12 +#define Y_DIR_PIN PA11 +#define Y_ENABLE_PIN PA15 -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD3 -#define Z_ENABLE_PIN PB3 +#define Z_STEP_PIN PD6 +#define Z_DIR_PIN PD3 +#define Z_ENABLE_PIN PB3 // Extruder stepper pins // NOTE: Numbering here is made according to EXT connector numbers, @@ -86,46 +86,46 @@ // That is, E0_*_PIN are the E2_* lines connected to E2_A1 step // stick that drives the EXT0 output on the board. // -#define E0_STEP_PIN PC14 -#define E0_DIR_PIN PC13 -#define E0_ENABLE_PIN PC15 +#define E0_STEP_PIN PC14 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PC15 -#define E1_STEP_PIN PA0 -#define E1_DIR_PIN PB6 -#define E1_ENABLE_PIN PA1 +#define E1_STEP_PIN PA0 +#define E1_DIR_PIN PB6 +#define E1_ENABLE_PIN PA1 -#define E2_STEP_PIN PB2 -#define E2_DIR_PIN PB11 -#define E2_ENABLE_PIN PC4 +#define E2_STEP_PIN PB2 +#define E2_DIR_PIN PB11 +#define E2_ENABLE_PIN PC4 // // Heaters / Fans // -#define HEATER_0_PIN PB0 // EXT0 port -#define HEATER_1_PIN PB5 // EXT1 port -#define HEATER_2_PIN PB4 // EXT2 port -#define HEATER_BED_PIN PB1 // CON2X3 hotbed port +#define HEATER_0_PIN PB0 // EXT0 port +#define HEATER_1_PIN PB5 // EXT1 port +#define HEATER_2_PIN PB4 // EXT2 port +#define HEATER_BED_PIN PB1 // CON2X3 hotbed port // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan -#define FAN1_PIN PB8 // EXT1 port -#define FAN2_PIN PB7 // EXT2 port +//#define FAN_PIN PB9 // EXT0 port +#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#define FAN1_PIN PB8 // EXT1 port +#define FAN2_PIN PB7 // EXT2 port // // Temperature Sensors // -#define TEMP_0_PIN PC2 // EXT0 port -#define TEMP_1_PIN PC1 // EXT1 port -#define TEMP_2_PIN PC0 // EXT2 port -#define TEMP_BED_PIN PC3 // CON2X3 hotbed port +#define TEMP_0_PIN PC2 // EXT0 port +#define TEMP_1_PIN PC1 // EXT1 port +#define TEMP_2_PIN PC0 // EXT2 port +#define TEMP_BED_PIN PC3 // CON2X3 hotbed port // // Misc. Functions // -#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector +#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector // // LCD / Controller @@ -139,16 +139,16 @@ // RepRapDiscount Smart Controller, but adds an FFC40 connector // connected with a flat wire to J2 connector on the board. // - #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) - #define LCD_PINS_D4 PD8 // SCK (CLK) clock - #define LCD_PINS_D5 PD9 - #define LCD_PINS_D6 PD10 - #define LCD_PINS_D7 PE15 + #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_D4 PD8 // SCK (CLK) clock + #define LCD_PINS_D5 PD9 + #define LCD_PINS_D6 PD10 + #define LCD_PINS_D7 PE15 - #define BTN_EN1 PE8 - #define BTN_EN2 PE9 - #define BTN_ENC PE13 + #define BTN_EN1 PE8 + #define BTN_EN2 PE9 + #define BTN_ENC PE13 #define GTM32_PRO_VB_USE_LCD_BEEPER #define GTM32_PRO_VB_USE_EXT_SDCARD @@ -157,8 +157,8 @@ // // Serial LCDs can be implemented in ExtUI // - //#define LCD_UART_TX PD8 - //#define LCD_UART_RX PD9 + //#define LCD_UART_TX PD8 + //#define LCD_UART_RX PD9 #endif #if HAS_GRAPHICAL_LCD @@ -182,10 +182,10 @@ // This is pin 32 on J2 FFC40 and pin, goes to the beeper // on Geeetech's version of RepRapDiscount Smart Controller // (e.g. on Rostock 301) - #define BEEPER_PIN PE12 + #define BEEPER_PIN PE12 #else // This is the beeper on the board itself - #define BEEPER_PIN PB10 + #define BEEPER_PIN PB10 #endif /** @@ -203,28 +203,28 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PC11 - #define SCK_PIN PC12 - #define MOSI_PIN PD2 - #define MISO_PIN PC8 - #define SD_DETECT_PIN PC7 + #define SS_PIN PC11 + #define SCK_PIN PC12 + #define MOSI_PIN PD2 + #define MISO_PIN PC8 + #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 - #define SD_DETECT_PIN -1 // Card detect is not connected + #define SS_PIN PA4 + #define SCK_PIN PA5 + #define MOSI_PIN PA7 + #define MISO_PIN PA6 + #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. // Must define WIFISUPPORT in Configuration.h for the printer. // -#define ESP_WIFI_MODULE_COM 2 -#define ESP_WIFI_MODULE_BAUDRATE 115200 -#define ESP_WIFI_MODULE_RESET_PIN -1 +#define ESP_WIFI_MODULE_COM 2 +#define ESP_WIFI_MODULE_BAUDRATE 115200 +#define ESP_WIFI_MODULE_RESET_PIN -1 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index a35bd29888..38cc615f64 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -53,32 +53,32 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB // // Limit Switches // -#define X_MIN_PIN PE5 // ENDSTOPS 15,17 -#define X_MAX_PIN PE4 // ENDSTOPS 16,18 -#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 -#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 -#define Z_MIN_PIN PE1 // ENDSTOPS 3,5 -#define Z_MAX_PIN PE0 // ENDSTOPS 4,6 +#define X_MIN_PIN PE5 // ENDSTOPS 15,17 +#define X_MAX_PIN PE4 // ENDSTOPS 16,18 +#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 +#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 +#define Z_MIN_PIN PE1 // ENDSTOPS 3,5 +#define Z_MAX_PIN PE0 // ENDSTOPS 4,6 // // Steppers // -#define X_STEP_PIN PC6 -#define X_DIR_PIN PD13 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PD13 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PA12 -#define Y_DIR_PIN PA11 -#define Y_ENABLE_PIN PA15 +#define Y_STEP_PIN PA12 +#define Y_DIR_PIN PA11 +#define Y_ENABLE_PIN PA15 -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD3 -#define Z_ENABLE_PIN PB3 +#define Z_STEP_PIN PD6 +#define Z_DIR_PIN PD3 +#define Z_ENABLE_PIN PB3 // Extruder stepper pins // NOTE: Numbering here is made according to EXT connector numbers, @@ -86,46 +86,46 @@ // That is, E0_*_PIN are the E2_* lines connected to E2_A1 step // stick that drives the EXT0 output on the board. // -#define E0_STEP_PIN PC14 -#define E0_DIR_PIN PC13 -#define E0_ENABLE_PIN PC15 +#define E0_STEP_PIN PC14 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PC15 -#define E1_STEP_PIN PA0 -#define E1_DIR_PIN PB6 -#define E1_ENABLE_PIN PA1 +#define E1_STEP_PIN PA0 +#define E1_DIR_PIN PB6 +#define E1_ENABLE_PIN PA1 -#define E2_STEP_PIN PB2 -#define E2_DIR_PIN PB11 -#define E2_ENABLE_PIN PC4 +#define E2_STEP_PIN PB2 +#define E2_DIR_PIN PB11 +#define E2_ENABLE_PIN PC4 // // Heaters / Fans // -#define HEATER_0_PIN PB0 // EXT0 port -#define HEATER_1_PIN PB5 // EXT1 port -#define HEATER_2_PIN PB4 // EXT2 port -#define HEATER_BED_PIN PB1 // CON2X3 hotbed port +#define HEATER_0_PIN PB0 // EXT0 port +#define HEATER_1_PIN PB5 // EXT1 port +#define HEATER_2_PIN PB4 // EXT2 port +#define HEATER_BED_PIN PB1 // CON2X3 hotbed port // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan -#define FAN1_PIN PB8 // EXT1 port -#define FAN2_PIN PB7 // EXT2 port +//#define FAN_PIN PB9 // EXT0 port +#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#define FAN1_PIN PB8 // EXT1 port +#define FAN2_PIN PB7 // EXT2 port // // Temperature Sensors // -#define TEMP_0_PIN PC2 // EXT0 port -#define TEMP_1_PIN PC1 // EXT1 port -#define TEMP_2_PIN PC0 // EXT2 port -#define TEMP_BED_PIN PC3 // CON2X3 hotbed port +#define TEMP_0_PIN PC2 // EXT0 port +#define TEMP_1_PIN PC1 // EXT1 port +#define TEMP_2_PIN PC0 // EXT2 port +#define TEMP_BED_PIN PC3 // CON2X3 hotbed port // // Misc. Functions // -#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector +#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector // // LCD / Controller @@ -138,19 +138,19 @@ // Geeetech's LCD2004A Control Panel is very much like // RepRapDiscount Smart Controller, but adds an FFC40 connector // - #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) - #define LCD_PINS_D4 PD8 // SCK (CLK) clock - #define LCD_PINS_D5 PD9 - #define LCD_PINS_D6 PD10 - #define LCD_PINS_D7 PE15 + #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_D4 PD8 // SCK (CLK) clock + #define LCD_PINS_D5 PD9 + #define LCD_PINS_D6 PD10 + #define LCD_PINS_D7 PE15 #else // // Serial LCDs can be implemented in ExtUI // - //#define LCD_UART_TX PD8 - //#define LCD_UART_RX PD9 + //#define LCD_UART_TX PD8 + //#define LCD_UART_RX PD9 #endif #if HAS_GRAPHICAL_LCD @@ -167,9 +167,9 @@ // RepRapDiscount Smart Controller, but adds an FFC40 connector // connected with a flat wire to J2 connector on the board. // - #define BTN_EN1 PE8 - #define BTN_EN2 PE9 - #define BTN_ENC PE13 + #define BTN_EN1 PE8 + #define BTN_EN2 PE9 + #define BTN_ENC PE13 #define GTM32_PRO_VB_USE_LCD_BEEPER #define GTM32_PRO_VB_USE_EXT_SDCARD @@ -182,10 +182,10 @@ // This is pin 32 on J2 FFC40 and pin, goes to the beeper // on Geeetech's version of RepRapDiscount Smart Controller // (e.g. on Rostock 301) - #define BEEPER_PIN PE12 + #define BEEPER_PIN PE12 #else // This is the beeper on the board itself - #define BEEPER_PIN PB10 + #define BEEPER_PIN PB10 #endif /** @@ -203,28 +203,28 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PC11 - #define SCK_PIN PC12 - #define MOSI_PIN PD2 - #define MISO_PIN PC8 - #define SD_DETECT_PIN PC7 + #define SS_PIN PC11 + #define SCK_PIN PC12 + #define MOSI_PIN PD2 + #define MISO_PIN PC8 + #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 - #define SD_DETECT_PIN -1 // Card detect is not connected + #define SS_PIN PA4 + #define SCK_PIN PA5 + #define MOSI_PIN PA7 + #define MISO_PIN PA6 + #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. // Must define WIFISUPPORT in Configuration.h for the printer. // -#define ESP_WIFI_MODULE_COM 2 -#define ESP_WIFI_MODULE_BAUDRATE 115200 -#define ESP_WIFI_MODULE_RESET_PIN -1 +#define ESP_WIFI_MODULE_COM 2 +#define ESP_WIFI_MODULE_BAUDRATE 115200 +#define ESP_WIFI_MODULE_RESET_PIN -1 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index e02b8b9377..24196ad892 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -53,32 +53,32 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB // // Limit Switches // -#define X_MIN_PIN PE5 // ENDSTOPS 15,17 -#define X_MAX_PIN PE4 // ENDSTOPS 16,18 -#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 -#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 -#define Z_MIN_PIN PE1 // ENDSTOPS 3,5 -#define Z_MAX_PIN PE0 // ENDSTOPS 4,6 +#define X_MIN_PIN PE5 // ENDSTOPS 15,17 +#define X_MAX_PIN PE4 // ENDSTOPS 16,18 +#define Y_MIN_PIN PE3 // ENDSTOPS 9,11 +#define Y_MAX_PIN PE2 // ENDSTOPS 10,12 +#define Z_MIN_PIN PE1 // ENDSTOPS 3,5 +#define Z_MAX_PIN PE0 // ENDSTOPS 4,6 // // Steppers // -#define X_STEP_PIN PC6 -#define X_DIR_PIN PD13 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PD13 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PA12 -#define Y_DIR_PIN PA11 -#define Y_ENABLE_PIN PA15 +#define Y_STEP_PIN PA12 +#define Y_DIR_PIN PA11 +#define Y_ENABLE_PIN PA15 -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD3 -#define Z_ENABLE_PIN PB3 +#define Z_STEP_PIN PD6 +#define Z_DIR_PIN PD3 +#define Z_ENABLE_PIN PB3 // Extruder stepper pins // NOTE: Numbering here is made according to EXT connector numbers, @@ -86,46 +86,46 @@ // That is, E0_*_PIN are the E2_* lines connected to E2_A1 step // stick that drives the EXT0 output on the board. // -#define E0_STEP_PIN PC14 -#define E0_DIR_PIN PC13 -#define E0_ENABLE_PIN PC15 +#define E0_STEP_PIN PC14 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PC15 -#define E1_STEP_PIN PA0 -#define E1_DIR_PIN PB6 -#define E1_ENABLE_PIN PA1 +#define E1_STEP_PIN PA0 +#define E1_DIR_PIN PB6 +#define E1_ENABLE_PIN PA1 -#define E2_STEP_PIN PB2 -#define E2_DIR_PIN PB11 -#define E2_ENABLE_PIN PC4 +#define E2_STEP_PIN PB2 +#define E2_DIR_PIN PB11 +#define E2_ENABLE_PIN PC4 // // Heaters / Fans - INFO: Extruders ports are in reverse order. Pin numbers here differ from schematic. Original firmware assumes heater, fan and temp sensor on port EXT0 PB0, PB9, PC2. // -#define HEATER_0_PIN PB0 // EXT0 port. -#define HEATER_1_PIN PB5 // EXT1 port -#define HEATER_2_PIN PB4 // EXT2 port -#define HEATER_BED_PIN PB1 // CON2X3 hotbed port +#define HEATER_0_PIN PB0 // EXT0 port. +#define HEATER_1_PIN PB5 // EXT1 port +#define HEATER_2_PIN PB4 // EXT2 port +#define HEATER_BED_PIN PB1 // CON2X3 hotbed port // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port -#define FAN1_PIN PB8 // EXT1 port -#define FAN2_PIN PB7 // EXT2 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +//#define FAN_PIN PB9 // EXT0 port +#define FAN1_PIN PB8 // EXT1 port +#define FAN2_PIN PB7 // EXT2 port +#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan // // Temperature Sensors // -#define TEMP_0_PIN PC2 // EXT0 port -#define TEMP_1_PIN PC1 // EXT1 port -#define TEMP_2_PIN PC0 // EXT2 port -#define TEMP_BED_PIN PC3 // CON2X3 hotbed port +#define TEMP_0_PIN PC2 // EXT0 port +#define TEMP_1_PIN PC1 // EXT1 port +#define TEMP_2_PIN PC0 // EXT2 port +#define TEMP_BED_PIN PC3 // CON2X3 hotbed port // // Misc. Functions // -#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector +#define LED_PWM PD12 // External LED, pin 2 on LED labeled connector // // LCD / Controller @@ -140,16 +140,16 @@ // RepRapDiscount Smart Controller, but adds an FFC40 connector // connected with a flat wire to J2 connector on the board. // - #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) - #define LCD_PINS_D4 PD8 // SCK (CLK) clock - #define LCD_PINS_D5 PD9 - #define LCD_PINS_D6 PD10 - #define LCD_PINS_D7 PE15 + #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_D4 PD8 // SCK (CLK) clock + #define LCD_PINS_D5 PD9 + #define LCD_PINS_D6 PD10 + #define LCD_PINS_D7 PE15 - #define BTN_EN1 PE8 - #define BTN_EN2 PE9 - #define BTN_ENC PE13 + #define BTN_EN1 PE8 + #define BTN_EN2 PE9 + #define BTN_ENC PE13 //#define GTM32_PRO_VB_USE_LCD_BEEPER #define GTM32_PRO_VB_USE_EXT_SDCARD @@ -158,19 +158,19 @@ // // Serial LCDs can be implemented in ExtUI // - //#define LCD_UART_TX PD8 - //#define LCD_UART_RX PD9 + //#define LCD_UART_TX PD8 + //#define LCD_UART_RX PD9 #endif #if HAS_GRAPHICAL_LCD #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(96) + #define ST7920_DELAY_1 DELAY_NS(96) #endif #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(48) + #define ST7920_DELAY_2 DELAY_NS(48) #endif #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(715) + #define ST7920_DELAY_3 DELAY_NS(715) #endif #endif @@ -183,10 +183,10 @@ // This is pin 32 on J2 FFC40 and pin, goes to the beeper // on Geeetech's version of RepRapDiscount Smart Controller // (e.g. on Rostock 301) - #define BEEPER_PIN PE12 + #define BEEPER_PIN PE12 #else // This is the beeper on the board itself - #define BEEPER_PIN PB10 + #define BEEPER_PIN PB10 #endif /** @@ -204,29 +204,29 @@ // // SD Card on RepRapDiscount Smart Controller (J2) or on SD_CARD connector // - #define SS_PIN PB12 // PC11 - #define SCK_PIN PB13 // PC12 // PC1 - #define MOSI_PIN PB15 // PD2 // PD2 - #define MISO_PIN PB14 // PC8 - #define SD_DETECT_PIN PC7 + #define SS_PIN PB12 // PC11 + #define SCK_PIN PB13 // PC12 // PC1 + #define MOSI_PIN PB15 // PD2 // PD2 + #define MISO_PIN PB14 // PC8 + #define SD_DETECT_PIN PC7 #else // // Use the on-board card socket labeled TF_CARD_SOCKET // - #define SS_PIN PA4 - #define SCK_PIN PA5 - #define MOSI_PIN PA7 - #define MISO_PIN PA6 // PA6 - #define SD_DETECT_PIN -1 // Card detect is not connected + #define SS_PIN PA4 + #define SCK_PIN PA5 + #define MOSI_PIN PA7 + #define MISO_PIN PA6 // PA6 + #define SD_DETECT_PIN -1 // Card detect is not connected #endif -#define SDSS SS_PIN +#define SDSS SS_PIN // // ESP WiFi can be soldered to J9 connector which is wired to USART2. // Must define WIFISUPPORT in Configuration.h for the printer. // -#define ESP_WIFI_MODULE_COM 2 -#define ESP_WIFI_MODULE_BAUDRATE 115200 -#define ESP_WIFI_MODULE_RESET_PIN -1 +#define ESP_WIFI_MODULE_COM 2 +#define ESP_WIFI_MODULE_BAUDRATE 115200 +#define ESP_WIFI_MODULE_RESET_PIN -1 diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 3849af3ae3..6395f6efc9 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -42,10 +42,10 @@ // #define MCU_STM32F103ZE // not yet required // Enable EEPROM Emulation for this board, so that we don't overwrite factory data -//#define I2C_EEPROM // AT24C64 -//#define E2END 0x7FFF // 64KB +//#define I2C_EEPROM // AT24C64 +//#define E2END 0x7FFF // 64KB //#define FLASH_EEPROM_EMULATION -//#define E2END 0xFFF // 4KB +//#define E2END 0xFFF // 4KB //#define E2END uint32(EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE * 2) - 1) //#define EEPROM_CHITCHAT //#define DEBUG_EEPROM_READWRITE @@ -53,78 +53,78 @@ // // Limit Switches // -#define X_STOP_PIN PC6 -#define Y_STOP_PIN PG8 -#define Z_STOP_PIN PG7 -//#define X_MAX_PIN PC5 -//#define Y_MAX_PIN PC4 -//#define Z_MAX_PIN PB0 +#define X_STOP_PIN PC6 +#define Y_STOP_PIN PG8 +#define Z_STOP_PIN PG7 +//#define X_MAX_PIN PC5 +//#define Y_MAX_PIN PC4 +//#define Z_MAX_PIN PB0 // // Steppers // -#define X_STEP_PIN PD6 -#define X_DIR_PIN PD3 -#define X_ENABLE_PIN PG9 +#define X_STEP_PIN PD6 +#define X_DIR_PIN PD3 +#define X_ENABLE_PIN PG9 -#define Y_STEP_PIN PG12 -#define Y_DIR_PIN PG11 -#define Y_ENABLE_PIN PG13 +#define Y_STEP_PIN PG12 +#define Y_DIR_PIN PG11 +#define Y_ENABLE_PIN PG13 -#define Z_STEP_PIN PG15 -#define Z_DIR_PIN PG14 -#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PG15 +#define Z_DIR_PIN PG14 +#define Z_ENABLE_PIN PB8 -#define E0_STEP_PIN PE2 -#define E0_DIR_PIN PB9 -#define E0_ENABLE_PIN PE3 +#define E0_STEP_PIN PE2 +#define E0_DIR_PIN PB9 +#define E0_ENABLE_PIN PE3 -#define E1_STEP_PIN PE5 -#define E1_DIR_PIN PE4 -#define E1_ENABLE_PIN PE6 +#define E1_STEP_PIN PE5 +#define E1_DIR_PIN PE4 +#define E1_ENABLE_PIN PE6 // // Temperature Sensors // -#define TEMP_0_PIN PC2 -#define TEMP_BED_PIN PC1 +#define TEMP_0_PIN PC2 +#define TEMP_BED_PIN PC1 // // Heaters / Fans // -#define HEATER_0_PIN PA2 -#define HEATER_BED_PIN PA3 +#define HEATER_0_PIN PA2 +#define HEATER_BED_PIN PA3 -#define FAN_PIN PA1 +#define FAN_PIN PA1 -#define FIL_RUNOUT_PIN PC7 +#define FIL_RUNOUT_PIN PC7 // // LCD // -#define LCD_BACKLIGHT_PIN PF11 -#define FSMC_CS_PIN PD7 -#define FSMC_RS_PIN PG0 +#define LCD_BACKLIGHT_PIN PF11 +#define FSMC_CS_PIN PD7 +#define FSMC_RS_PIN PG0 -#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT -#define FSMC_DMA_DEV DMA2 -#define FSMC_DMA_CHANNEL DMA_CH5 +#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT +#define FSMC_DMA_DEV DMA2 +#define FSMC_DMA_CHANNEL DMA_CH5 // // SD Card // -#define SD_DETECT_PIN PF10 +#define SD_DETECT_PIN PF10 // // Misc. // -#define BEEPER_PIN PC3 // use PB7 to shut up if desired -#define LED_PIN PC13 +#define BEEPER_PIN PC3 // use PB7 to shut up if desired +#define LED_PIN PC13 // // Touch support // #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PA4 - #define TOUCH_INT_PIN PC4 + #define TOUCH_CS_PIN PA4 + #define TOUCH_INT_PIN PC4 #endif diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 66c5b55ecb..83881c128d 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -29,20 +29,20 @@ #endif #define BOARD_INFO_NAME "Longer3D" -#define ALFAWISE_UX0 // Common to all Longer3D STM32F1 boards (used for Open drain mosfets) +#define ALFAWISE_UX0 // Common to all Longer3D STM32F1 boards (used for Open drain mosfets) -//#define DISABLE_DEBUG // We still want to debug with STLINK... -#define DISABLE_JTAG // We free the jtag pins (PA15) but keep STLINK - // Release PB4 (STEP_X_PIN) from JTAG NRST role. +//#define DISABLE_DEBUG // We still want to debug with STLINK... +#define DISABLE_JTAG // We free the jtag pins (PA15) but keep STLINK + // Release PB4 (STEP_X_PIN) from JTAG NRST role. // // Limit Switches // -#define X_MIN_PIN PC1 // pin 16 -#define X_MAX_PIN PC0 // pin 15 (Filament sensor on Alfawise setup) -#define Y_MIN_PIN PC15 // pin 9 -#define Y_MAX_PIN PC14 // pin 8 (Unused in stock Alfawise setup) -#define Z_MIN_PIN PE6 // pin 5 Standard Endstop or Z_Probe endstop function -#define Z_MAX_PIN PE5 // pin 4 (Unused in stock Alfawise setup) +#define X_MIN_PIN PC1 // pin 16 +#define X_MAX_PIN PC0 // pin 15 (Filament sensor on Alfawise setup) +#define Y_MIN_PIN PC15 // pin 9 +#define Y_MAX_PIN PC14 // pin 8 (Unused in stock Alfawise setup) +#define Z_MIN_PIN PE6 // pin 5 Standard Endstop or Z_Probe endstop function +#define Z_MAX_PIN PE5 // pin 4 (Unused in stock Alfawise setup) // May be used for BLTouch Servo function on older variants (<= V08) #define ONBOARD_ENDSTOPPULLUPS @@ -50,60 +50,60 @@ // Filament Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PC0 // XMAX plug on PCB used as filament runout sensor on Alfawise boards (inverting true) + #define FIL_RUNOUT_PIN PC0 // XMAX plug on PCB used as filament runout sensor on Alfawise boards (inverting true) #endif // // Steppers // -#define X_ENABLE_PIN PB5 // pin 91 -#define X_STEP_PIN PB4 // pin 90 -#define X_DIR_PIN PB3 // pin 89 +#define X_ENABLE_PIN PB5 // pin 91 +#define X_STEP_PIN PB4 // pin 90 +#define X_DIR_PIN PB3 // pin 89 -#define Y_ENABLE_PIN PB8 // pin 95 -#define Y_STEP_PIN PB7 // pin 93 -#define Y_DIR_PIN PB6 // pin 92 +#define Y_ENABLE_PIN PB8 // pin 95 +#define Y_STEP_PIN PB7 // pin 93 +#define Y_DIR_PIN PB6 // pin 92 -#define Z_ENABLE_PIN PE1 // pin 98 -#define Z_STEP_PIN PE0 // pin 97 -#define Z_DIR_PIN PB9 // pin 96 +#define Z_ENABLE_PIN PE1 // pin 98 +#define Z_STEP_PIN PE0 // pin 97 +#define Z_DIR_PIN PB9 // pin 96 -#define E0_ENABLE_PIN PE4 // pin 3 -#define E0_STEP_PIN PE3 // pin 2 -#define E0_DIR_PIN PE2 // pin 1 +#define E0_ENABLE_PIN PE4 // pin 3 +#define E0_STEP_PIN PE3 // pin 2 +#define E0_DIR_PIN PE2 // pin 1 // // Temperature Sensors // -#define TEMP_0_PIN PA0 // pin 23 (Nozzle 100K/3950 thermistor) -#define TEMP_BED_PIN PA1 // pin 24 (Hot Bed 100K/3950 thermistor) +#define TEMP_0_PIN PA0 // pin 23 (Nozzle 100K/3950 thermistor) +#define TEMP_BED_PIN PA1 // pin 24 (Hot Bed 100K/3950 thermistor) // // Heaters / Fans // -#define HEATER_0_PIN PD3 // pin 84 (Nozzle Heat Mosfet) -#define HEATER_BED_PIN PA8 // pin 67 (Hot Bed Mosfet) +#define HEATER_0_PIN PD3 // pin 84 (Nozzle Heat Mosfet) +#define HEATER_BED_PIN PA8 // pin 67 (Hot Bed Mosfet) -#define FAN_PIN PA15 // pin 77 (4cm Fan) -#define FAN_SOFT_PWM // Required to avoid issues with heating or STLink -#define FAN_MIN_PWM 35 // Fan will not start in 1-30 range -#define FAN_MAX_PWM 255 +#define FAN_PIN PA15 // pin 77 (4cm Fan) +#define FAN_SOFT_PWM // Required to avoid issues with heating or STLink +#define FAN_MIN_PWM 35 // Fan will not start in 1-30 range +#define FAN_MAX_PWM 255 -//#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor +//#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor // Can drive a PC Buzzer, if connected between PWM and 5V pins -#define LED_PIN PC2 // pin 17 +#define LED_PIN PC2 // pin 17 // // PWM for a servo probe // Other servo devices are not supported on this board! // #if HAS_Z_SERVO_PROBE - #define SERVO0_PIN PD13 // Open drain PWM pin on the V0G (GND or floating 5V) - #define SERVO0_PWM_OD // Comment this if using PE5 + #define SERVO0_PIN PD13 // Open drain PWM pin on the V0G (GND or floating 5V) + #define SERVO0_PWM_OD // Comment this if using PE5 - //#define SERVO0_PIN PE5 // Pulled up PWM pin on the V08 (3.3V or 0) - //#undef Z_MAX_PIN // Uncomment if using ZMAX connector (PE5) + //#define SERVO0_PIN PE5 // Pulled up PWM pin on the V08 (3.3V or 0) + //#undef Z_MAX_PIN // Uncomment if using ZMAX connector (PE5) #endif /** @@ -118,17 +118,17 @@ * because Marlin uses the reset as a failsafe to revive a glitchy LCD. */ -#define LCD_RESET_PIN PC4 // pin 33 -#define LCD_BACKLIGHT_PIN PD12 // pin 59 -#define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 -#define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed +#define LCD_RESET_PIN PC4 // pin 33 +#define LCD_BACKLIGHT_PIN PD12 // pin 59 +#define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 +#define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed -#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT -#define FSMC_DMA_DEV DMA2 -#define FSMC_DMA_CHANNEL DMA_CH5 +#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT +#define FSMC_DMA_DEV DMA2 +#define FSMC_DMA_CHANNEL DMA_CH5 -#define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h -#define DOGLCD_SCK -1 +#define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h +#define DOGLCD_SCK -1 /** * Note: Alfawise U20/U30 boards DON'T use SPI2, as the hardware designer @@ -136,11 +136,11 @@ * declared below. */ #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PB12 // pin 51 SPI2_NSS - #define TOUCH_SCK_PIN PB13 // pin 52 - #define TOUCH_MOSI_PIN PB14 // pin 53 - #define TOUCH_MISO_PIN PB15 // pin 54 - #define TOUCH_INT_PIN PC6 // pin 63 (PenIRQ coming from ADS7843) + #define TOUCH_CS_PIN PB12 // pin 51 SPI2_NSS + #define TOUCH_SCK_PIN PB13 // pin 52 + #define TOUCH_MOSI_PIN PB14 // pin 53 + #define TOUCH_MISO_PIN PB15 // pin 54 + #define TOUCH_INT_PIN PC6 // pin 63 (PenIRQ coming from ADS7843) #endif // @@ -153,12 +153,12 @@ #undef E2END #if ENABLED(SPI_EEPROM) // SPI1 EEPROM Winbond W25Q64 (8MB/64Mbits) - #define SPI_CHAN_EEPROM1 1 - #define SPI_EEPROM1_CS PC5 // pin 34 - #define EEPROM_SCK BOARD_SPI1_SCK_PIN // PA5 pin 30 - #define EEPROM_MISO BOARD_SPI1_MISO_PIN // PA6 pin 31 - #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 - #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) + #define SPI_CHAN_EEPROM1 1 + #define SPI_EEPROM1_CS PC5 // pin 34 + #define EEPROM_SCK BOARD_SPI1_SCK_PIN // PA5 pin 30 + #define EEPROM_MISO BOARD_SPI1_MISO_PIN // PA6 pin 31 + #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 + #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) #define E2END ((16 * EEPROM_PAGE_SIZE)-1) // Limit to 64KB for now... #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 624c59ebea..9829018d8d 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -36,7 +36,7 @@ // but it is literally the only board which uses it. #define FLASH_EEPROM_EMULATION -#define SDSS SS_PIN +#define SDSS SS_PIN // Based on PWM timer usage, we have to use these timers and soft PWM for the fans // On STM32F103: @@ -50,43 +50,43 @@ // // Limit Switches // -#define X_MIN_PIN PB4 -#define Y_MIN_PIN PA15 -#define Z_MIN_PIN PB5 +#define X_MIN_PIN PB4 +#define Y_MIN_PIN PA15 +#define Z_MIN_PIN PB5 // // Steppers // // X & Y enable are the same -#define X_STEP_PIN PB14 -#define X_DIR_PIN PB15 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PB14 +#define X_DIR_PIN PB15 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PB12 -#define Y_DIR_PIN PB13 -#define Y_ENABLE_PIN PA8 +#define Y_STEP_PIN PB12 +#define Y_DIR_PIN PB13 +#define Y_ENABLE_PIN PA8 -#define Z_STEP_PIN PB10 -#define Z_DIR_PIN PB2 -#define Z_ENABLE_PIN PB11 +#define Z_STEP_PIN PB10 +#define Z_DIR_PIN PB2 +#define Z_ENABLE_PIN PB11 -#define E0_STEP_PIN PB0 -#define E0_DIR_PIN PC13 -#define E0_ENABLE_PIN PB1 +#define E0_STEP_PIN PB0 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PB1 // // Temperature Sensors // -#define TEMP_0_PIN PA0 // Analog Input (HOTEND0 thermistor) -#define TEMP_BED_PIN PA1 // Analog Input (BED thermistor) +#define TEMP_0_PIN PA0 // Analog Input (HOTEND0 thermistor) +#define TEMP_BED_PIN PA1 // Analog Input (BED thermistor) // // Heaters / Fans // -#define HEATER_0_PIN PB6 // HOTEND0 MOSFET -#define HEATER_BED_PIN PB7 // BED MOSFET +#define HEATER_0_PIN PB6 // HOTEND0 MOSFET +#define HEATER_BED_PIN PB7 // BED MOSFET -#define MALYAN_FAN1_PIN PB8 // FAN1 header on board - PRINT FAN -#define MALYAN_FAN2_PIN PB3 // FAN2 header on board - CONTROLLER FAN +#define MALYAN_FAN1_PIN PB8 // FAN1 header on board - PRINT FAN +#define MALYAN_FAN2_PIN PB3 // FAN2 header on board - CONTROLLER FAN -#define FAN1_PIN MALYAN_FAN2_PIN +#define FAN1_PIN MALYAN_FAN2_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 3b10bae139..db35548e88 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -43,72 +43,72 @@ // // Servos // -#define SERVO0_PIN PC3 // XS1 - 5 -#define SERVO1_PIN PA1 // XS1 - 6 -#define SERVO2_PIN PF9 // XS2 - 5 -#define SERVO3_PIN PF8 // XS2 - 6 +#define SERVO0_PIN PC3 // XS1 - 5 +#define SERVO1_PIN PA1 // XS1 - 6 +#define SERVO2_PIN PF9 // XS2 - 5 +#define SERVO3_PIN PF8 // XS2 - 6 // // Limit Switches // -#define X_MIN_PIN PB12 -#define X_MAX_PIN PB0 -#define Y_MIN_PIN PC5 -#define Y_MAX_PIN PC4 -#define Z_MIN_PIN PA4 -#define Z_MAX_PIN PF7 +#define X_MIN_PIN PB12 +#define X_MAX_PIN PB0 +#define Y_MIN_PIN PC5 +#define Y_MAX_PIN PC4 +#define Z_MIN_PIN PA4 +#define Z_MAX_PIN PF7 // // Steppers // -#define X_ENABLE_PIN PB9 -#define X_STEP_PIN PB8 -#define X_DIR_PIN PB5 +#define X_ENABLE_PIN PB9 +#define X_STEP_PIN PB8 +#define X_DIR_PIN PB5 -#define Y_ENABLE_PIN PB4 -#define Y_STEP_PIN PG15 -#define Y_DIR_PIN PG10 +#define Y_ENABLE_PIN PB4 +#define Y_STEP_PIN PG15 +#define Y_DIR_PIN PG10 -#define Z_ENABLE_PIN PD7 -#define Z_STEP_PIN PD3 -#define Z_DIR_PIN PG14 +#define Z_ENABLE_PIN PD7 +#define Z_STEP_PIN PD3 +#define Z_DIR_PIN PG14 -#define E0_ENABLE_PIN PG13 -#define E0_STEP_PIN PG8 -#define E0_DIR_PIN PA15 +#define E0_ENABLE_PIN PG13 +#define E0_STEP_PIN PG8 +#define E0_DIR_PIN PA15 -#define E1_ENABLE_PIN PA12 -#define E1_STEP_PIN PA11 -#define E1_DIR_PIN PA8 +#define E1_ENABLE_PIN PA12 +#define E1_STEP_PIN PA11 +#define E1_DIR_PIN PA8 // // Temperature Sensors // -#define TEMP_0_PIN PC1 // TH1 -#define TEMP_1_PIN PC2 // TH2 -#define TEMP_BED_PIN PC0 // TB1 +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PC2 // TH2 +#define TEMP_BED_PIN PC0 // TB1 // // Heaters / Fans // -#define HEATER_0_PIN PC7 // HEATER1 -#define HEATER_1_PIN PA6 // HEATER2 -#define HEATER_BED_PIN PC6 // HOT BED +#define HEATER_0_PIN PC7 // HEATER1 +#define HEATER_1_PIN PA6 // HEATER2 +#define HEATER_BED_PIN PC6 // HOT BED -#define FAN_PIN PA7 // FAN +#define FAN_PIN PA7 // FAN /** * Note: MKS Robin board is using SPI2 interface. Make sure your stm32duino library is configured accordingly */ -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define MAX6675_SS_PIN PE5 // TC1 - CS1 +//#define MAX6675_SS_PIN PE6 // TC2 - CS2 -#define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PA3 // PW_OFF -#define FIL_RUNOUT_PIN PF11 // MT_DET +#define POWER_LOSS_PIN PA2 // PW_DET +#define PS_ON_PIN PA3 // PW_OFF +#define FIL_RUNOUT_PIN PF11 // MT_DET -#define BEEPER_PIN PC13 -#define LED_PIN PB2 +#define BEEPER_PIN PC13 +#define LED_PIN PB2 /** * Note: MKS Robin TFT screens use various TFT controllers @@ -122,38 +122,38 @@ * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu * because Marlin uses the reset as a failsafe to revive a glitchy LCD. */ -//#define LCD_RESET_PIN PF6 -#define LCD_BACKLIGHT_PIN PG11 -#define FSMC_CS_PIN PG12 // NE4 -#define FSMC_RS_PIN PF0 // A0 +//#define LCD_RESET_PIN PF6 +#define LCD_BACKLIGHT_PIN PG11 +#define FSMC_CS_PIN PG12 // NE4 +#define FSMC_RS_PIN PF0 // A0 -#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT -#define FSMC_DMA_DEV DMA2 -#define FSMC_DMA_CHANNEL DMA_CH5 +#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT +#define FSMC_DMA_DEV DMA2 +#define FSMC_DMA_CHANNEL DMA_CH5 #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PB1 // SPI2_NSS - #define TOUCH_SCK_PIN PB13 // SPI2_SCK - #define TOUCH_MISO_PIN PB14 // SPI2_MISO - #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI + #define TOUCH_CS_PIN PB1 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 // SPI2_SCK + #define TOUCH_MISO_PIN PB14 // SPI2_MISO + #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI #endif // SPI1(PA7) & SPI3(PB5) not available #define ENABLE_SPI2 #if ENABLED(SDIO_SUPPORT) - #define SCK_PIN PB13 // SPI2 - #define MISO_PIN PB14 // SPI2 - #define MOSI_PIN PB15 // SPI2 - #define SS_PIN -1 // PB12 is X- - #define SD_DETECT_PIN PF12 // SD_CD + #define SCK_PIN PB13 // SPI2 + #define MISO_PIN PB14 // SPI2 + #define MOSI_PIN PB15 // SPI2 + #define SS_PIN -1 // PB12 is X- + #define SD_DETECT_PIN PF12 // SD_CD #else // SD as custom software SPI (SDIO pins) - #define SCK_PIN PC12 - #define MISO_PIN PC8 - #define MOSI_PIN PD2 - #define SS_PIN -1 - #define ONBOARD_SD_CS_PIN PC11 - #define SDSS PD2 - #define SD_DETECT_PIN -1 + #define SCK_PIN PC12 + #define MISO_PIN PC8 + #define MOSI_PIN PD2 + #define SS_PIN -1 + #define ONBOARD_SD_CS_PIN PC11 + #define SDSS PD2 + #define SD_DETECT_PIN -1 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 1a7d664899..4c10a310bf 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -39,74 +39,74 @@ // // Limit Switches // -#define X_STOP_PIN PC13 -#define Y_STOP_PIN PC0 -#define Z_MIN_PIN PC12 -#define Z_MAX_PIN PB9 +#define X_STOP_PIN PC13 +#define Y_STOP_PIN PC0 +#define Z_MIN_PIN PC12 +#define Z_MAX_PIN PB9 // // Steppers // -#define X_STEP_PIN PC6 -#define X_DIR_PIN PB12 -#define X_ENABLE_PIN PB10 +#define X_STEP_PIN PC6 +#define X_DIR_PIN PB12 +#define X_ENABLE_PIN PB10 -#define Y_STEP_PIN PB11 -#define Y_DIR_PIN PB2 -#define Y_ENABLE_PIN PB10 +#define Y_STEP_PIN PB11 +#define Y_DIR_PIN PB2 +#define Y_ENABLE_PIN PB10 -#define Z_STEP_PIN PB1 -#define Z_DIR_PIN PC5 -#define Z_ENABLE_PIN PB10 +#define Z_STEP_PIN PB1 +#define Z_DIR_PIN PC5 +#define Z_ENABLE_PIN PB10 -#define E0_STEP_PIN PC4 -#define E0_DIR_PIN PA5 -#define E0_ENABLE_PIN PA4 +#define E0_STEP_PIN PC4 +#define E0_DIR_PIN PA5 +#define E0_ENABLE_PIN PA4 // // Heaters / Fans // -#define HEATER_0_PIN PC9 -#define FAN_PIN PA8 -#define HEATER_BED_PIN PC8 +#define HEATER_0_PIN PC9 +#define FAN_PIN PA8 +#define HEATER_BED_PIN PC8 // // Temperature Sensors // -#define TEMP_BED_PIN PA1 -#define TEMP_0_PIN PA0 +#define TEMP_BED_PIN PA1 +#define TEMP_0_PIN PA0 -#define FIL_RUNOUT_PIN PB8 // MT_DET +#define FIL_RUNOUT_PIN PB8 // MT_DET // // LCD Pins // #if HAS_SPI_LCD - #define BEEPER_PIN PD2 - #define BTN_ENC PB3 - #define LCD_PINS_RS PC3 + #define BEEPER_PIN PD2 + #define BTN_ENC PB3 + #define LCD_PINS_RS PC3 - #define BTN_EN1 PB5 - #define BTN_EN2 PB4 + #define BTN_EN1 PB5 + #define BTN_EN2 PB4 - #define LCD_PINS_ENABLE PC2 + #define LCD_PINS_ENABLE PC2 #if ENABLED(MKS_MINI_12864) - #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PC1 - #define DOGLCD_CS PC2 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 PC1 + #define DOGLCD_CS PC2 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 - #define LCD_PINS_D4 PC1 + #define LCD_PINS_D4 PC1 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 -1 - #define LCD_PINS_D6 -1 - #define LCD_PINS_D7 -1 + #define LCD_PINS_D5 -1 + #define LCD_PINS_D6 -1 + #define LCD_PINS_D7 -1 #endif #endif // !MKS_MINI_12864 @@ -114,9 +114,9 @@ #endif // HAS_SPI_LCD // Motor current PWM pins -#define MOTOR_CURRENT_PWM_XY_PIN PB0 -#define MOTOR_CURRENT_PWM_Z_PIN PA7 -#define MOTOR_CURRENT_PWM_E_PIN PA6 +#define MOTOR_CURRENT_PWM_XY_PIN PB0 +#define MOTOR_CURRENT_PWM_Z_PIN PA7 +#define MOTOR_CURRENT_PWM_E_PIN PA6 #define MOTOR_CURRENT_PWM_RANGE (65535/10/3.3) // (255 * (1000mA / 65535)) * 257 = 1000 is equal 1.6v Vref in turn equal 1Amp #define DEFAULT_PWM_MOTOR_CURRENT { 1000, 1000, 1000 } // 1.05Amp per driver, here is XY, Z and E. This values determined empirically. @@ -124,11 +124,11 @@ // SD Card // #define ENABLE_SPI2 -#define SD_DETECT_PIN PC10 -#define SCK_PIN PB13 -#define MISO_PIN P1B4 -#define MOSI_PIN P1B5 -#define SS_PIN PA15 +#define SD_DETECT_PIN PC10 +#define SCK_PIN PB13 +#define MISO_PIN P1B4 +#define MOSI_PIN P1B5 +#define SS_PIN PA15 #if HAS_GRAPHICAL_LCD #define BOARD_ST7920_DELAY_1 DELAY_NS(125) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index 9a404ec64d..466bdecc81 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -43,89 +43,89 @@ // // Servos // -#define SERVO0_PIN PA3 +#define SERVO0_PIN PA3 // // Limit Switches // -#define X_STOP_PIN PA12 -#define Y_STOP_PIN PA11 -#define Z_MIN_PIN PC6 -#define Z_MAX_PIN PB1 +#define X_STOP_PIN PA12 +#define Y_STOP_PIN PA11 +#define Z_MIN_PIN PC6 +#define Z_MAX_PIN PB1 // // Steppers // -#define X_STEP_PIN PC0 -#define X_DIR_PIN PB2 -#define X_ENABLE_PIN PC13 +#define X_STEP_PIN PC0 +#define X_DIR_PIN PB2 +#define X_ENABLE_PIN PC13 -#define Y_STEP_PIN PC2 -#define Y_DIR_PIN PB9 -#define Y_ENABLE_PIN PB12 +#define Y_STEP_PIN PC2 +#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PB12 -#define Z_STEP_PIN PB7 -#define Z_DIR_PIN PB6 -#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB7 +#define Z_DIR_PIN PB6 +#define Z_ENABLE_PIN PB8 -#define E0_STEP_PIN PB4 -#define E0_DIR_PIN PB3 -#define E0_ENABLE_PIN PB5 +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB3 +#define E0_ENABLE_PIN PB5 -#define E1_STEP_PIN PC12 -#define E1_DIR_PIN PC11 -#define E1_ENABLE_PIN PD2 +#define E1_STEP_PIN PC12 +#define E1_DIR_PIN PC11 +#define E1_ENABLE_PIN PD2 // // Heaters 0,1 / Fans / Bed // -#define HEATER_0_PIN PC9 -#define HEATER_1_PIN PC7 -#define FAN_PIN PA8 -#define HEATER_BED_PIN PC8 +#define HEATER_0_PIN PC9 +#define HEATER_1_PIN PC7 +#define FAN_PIN PA8 +#define HEATER_BED_PIN PC8 // // Temperature Sensors // -#define TEMP_BED_PIN PA1 //TB -#define TEMP_0_PIN PA0 //TH1 -#define TEMP_1_PIN PA2 //TH2 +#define TEMP_BED_PIN PA1 //TB +#define TEMP_0_PIN PA0 //TH1 +#define TEMP_1_PIN PA2 //TH2 -#define FIL_RUNOUT_PIN PB10 // MT_DET +#define FIL_RUNOUT_PIN PB10 // MT_DET // // LCD Pins // #if HAS_SPI_LCD - #define BEEPER_PIN PC1 - #define BTN_ENC PC3 - #define LCD_PINS_ENABLE PA4 - #define LCD_PINS_RS PA5 - #define BTN_EN1 PB11 - #define BTN_EN2 PB0 + #define BEEPER_PIN PC1 + #define BTN_ENC PC3 + #define LCD_PINS_ENABLE PA4 + #define LCD_PINS_RS PA5 + #define BTN_EN1 PB11 + #define BTN_EN2 PB0 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) - #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PC4 - #define DOGLCD_CS PA7 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 PC4 + #define DOGLCD_CS PA7 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 // Required for MKS_MINI_12864 with this board #define MKS_LCD12864B #undef SHOW_BOOTSCREEN - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 - #define LCD_PINS_D4 PA6 + #define LCD_PINS_D4 PA6 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PA7 - #define LCD_PINS_D6 PC4 - #define LCD_PINS_D7 PC5 + #define LCD_PINS_D5 PA7 + #define LCD_PINS_D6 PC4 + #define LCD_PINS_D7 PC5 #endif #endif // !MKS_MINI_12864 @@ -136,18 +136,18 @@ // SD Card // #define ENABLE_SPI2 -#define SD_DETECT_PIN PC10 -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 -#define SS_PIN PA15 +#define SD_DETECT_PIN PC10 +#define SCK_PIN PB13 +#define MISO_PIN PB14 +#define MOSI_PIN PB15 +#define SS_PIN PA15 #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(125) + #define ST7920_DELAY_1 DELAY_NS(125) #endif #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(125) + #define ST7920_DELAY_2 DELAY_NS(125) #endif #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(125) + #define ST7920_DELAY_3 DELAY_NS(125) #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 16e74b169e..50babad274 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -52,67 +52,67 @@ // // Limit Switches // -#define X_STOP_PIN PA15 -#define Y_STOP_PIN PA12 -#define Z_MIN_PIN PA11 -#define Z_MAX_PIN PC4 +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PA12 +#define Z_MIN_PIN PA11 +#define Z_MAX_PIN PC4 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA4 // MT_DET + #define FIL_RUNOUT_PIN PA4 // MT_DET #endif // // Steppers // -#define X_ENABLE_PIN PE4 -#define X_STEP_PIN PE3 -#define X_DIR_PIN PE2 +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 -#define Y_ENABLE_PIN PE1 -#define Y_STEP_PIN PE0 -#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 -#define Z_ENABLE_PIN PB8 -#define Z_STEP_PIN PB5 -#define Z_DIR_PIN PB4 +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 -#define E0_ENABLE_PIN PB3 -#define E0_STEP_PIN PD6 -#define E0_DIR_PIN PD3 +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 // // Temperature Sensors // -#define TEMP_0_PIN PC1 // TH1 -#define TEMP_BED_PIN PC0 // TB1 +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_BED_PIN PC0 // TB1 // // Heaters / Fans // -#define HEATER_0_PIN PC3 // HEATER1 -#define HEATER_BED_PIN PA0 // HOT BED +#define HEATER_0_PIN PC3 // HEATER1 +#define HEATER_BED_PIN PA0 // HOT BED -#define FAN_PIN PB1 // FAN +#define FAN_PIN PB1 // FAN // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define MAX6675_SS_PIN PE5 // TC1 - CS1 +//#define MAX6675_SS_PIN PE6 // TC2 - CS2 // // Misc. Functions // -#define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PA3 // PW_OFF +#define POWER_LOSS_PIN PA2 // PW_DET +#define PS_ON_PIN PA3 // PW_OFF -//#define LED_PIN PB2 +//#define LED_PIN PB2 // // LCD / Controller // -#define BEEPER_PIN PC5 -#define SD_DETECT_PIN PD12 +#define BEEPER_PIN PC5 +#define SD_DETECT_PIN PD12 /** * Note: MKS Robin TFT screens use various TFT controllers. @@ -120,27 +120,27 @@ * to let the bootloader init the screen. */ #if ENABLED(FSMC_GRAPHICAL_TFT) - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 - #define LCD_RESET_PIN PC6 - #define NO_LCD_REINIT // Suppress LCD re-initialization + #define LCD_RESET_PIN PC6 + #define NO_LCD_REINIT // Suppress LCD re-initialization - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_BACKLIGHT_PIN PD13 #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PC2 - #define TOUCH_SCK_PIN PB13 - #define TOUCH_MOSI_PIN PB15 - #define TOUCH_MISO_PIN PB14 + #define TOUCH_CS_PIN PC2 + #define TOUCH_SCK_PIN PB13 + #define TOUCH_MOSI_PIN PB15 + #define TOUCH_MISO_PIN PB14 #endif #endif // Motor current PWM pins -#define MOTOR_CURRENT_PWM_XY_PIN PA6 -#define MOTOR_CURRENT_PWM_Z_PIN PA7 -#define MOTOR_CURRENT_PWM_E_PIN PB0 -#define MOTOR_CURRENT_PWM_RANGE 1500 // (255 * (1000mA / 65535)) * 257 = 1000 is equal 1.6v Vref in turn equal 1Amp +#define MOTOR_CURRENT_PWM_XY_PIN PA6 +#define MOTOR_CURRENT_PWM_Z_PIN PA7 +#define MOTOR_CURRENT_PWM_E_PIN PB0 +#define MOTOR_CURRENT_PWM_RANGE 1500 // (255 * (1000mA / 65535)) * 257 = 1000 is equal 1.6v Vref in turn equal 1Amp #define DEFAULT_PWM_MOTOR_CURRENT { 1030, 1030, 1030 } // 1.05Amp per driver, here is XY, Z and E. This values determined empirically. // This is a kind of workaround in case native marlin "digipot" interface won't work. @@ -149,6 +149,6 @@ // #define MKS_ROBIN_MINI_VREF_PWM //#endif -//#define VREF_XY_PIN PA6 -//#define VREF_Z_PIN PA7 -//#define VREF_E1_PIN PB0 +//#define VREF_XY_PIN PA6 +//#define VREF_Z_PIN PA7 +//#define VREF_E1_PIN PB0 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 223f520ebe..ae9118e6d0 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -41,78 +41,78 @@ // // Limit Switches // -#define X_STOP_PIN PA15 -#define Y_STOP_PIN PA12 -#define Z_MIN_PIN PA11 -#define Z_MAX_PIN PC4 +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PA12 +#define Z_MIN_PIN PA11 +#define Z_MAX_PIN PC4 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA4 // MT_DET + #define FIL_RUNOUT_PIN PA4 // MT_DET #endif // // Steppers // -#define X_ENABLE_PIN PE4 -#define X_STEP_PIN PE3 -#define X_DIR_PIN PE2 +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 -#define Y_ENABLE_PIN PE1 -#define Y_STEP_PIN PE0 -#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 -#define Z_ENABLE_PIN PB8 -#define Z_STEP_PIN PB5 -#define Z_DIR_PIN PB4 +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 -#define E0_ENABLE_PIN PB3 -#define E0_STEP_PIN PD6 -#define E0_DIR_PIN PD3 +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 -#define E1_ENABLE_PIN PA3 -#define E1_STEP_PIN PA6 -#define E1_DIR_PIN PA1 +#define E1_ENABLE_PIN PA3 +#define E1_STEP_PIN PA6 +#define E1_DIR_PIN PA1 // // Temperature Sensors // -#define TEMP_0_PIN PC1 // TH1 -#define TEMP_1_PIN PC2 // TH2 -#define TEMP_BED_PIN PC0 // TB1 +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PC2 // TH2 +#define TEMP_BED_PIN PC0 // TB1 // // Heaters / Fans // -#define HEATER_0_PIN PC3 // HEATER1 -#define HEATER_1_PIN PB0 // HEATER2 -#define HEATER_BED_PIN PA0 // HOT BED +#define HEATER_0_PIN PC3 // HEATER1 +#define HEATER_1_PIN PB0 // HEATER2 +#define HEATER_BED_PIN PA0 // HOT BED -#define FAN_PIN PB1 // FAN +#define FAN_PIN PB1 // FAN // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define MAX6675_SS_PIN PE5 // TC1 - CS1 +//#define MAX6675_SS_PIN PE6 // TC2 - CS2 // // Misc. Functions // -#define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PA3 // PW_OFF +#define POWER_LOSS_PIN PA2 // PW_DET +#define PS_ON_PIN PA3 // PW_OFF -#define LED_PIN PB2 +#define LED_PIN PB2 // // SD Card // #define SDIO_SUPPORT -#define SD_DETECT_PIN PD12 +#define SD_DETECT_PIN PD12 // // LCD / Controller // -#define BEEPER_PIN PC5 +#define BEEPER_PIN PC5 /** * Note: MKS Robin TFT screens use various TFT controllers. @@ -120,18 +120,18 @@ * to let the bootloader init the screen. */ #if ENABLED(FSMC_GRAPHICAL_TFT) - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 - #define LCD_RESET_PIN PC6 // FSMC_RST - #define NO_LCD_REINIT // Suppress LCD re-initialization + #define LCD_RESET_PIN PC6 // FSMC_RST + #define NO_LCD_REINIT // Suppress LCD re-initialization - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_BACKLIGHT_PIN PD13 #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PA7 // SPI2_NSS - #define TOUCH_SCK_PIN PB13 // SPI2_SCK - #define TOUCH_MISO_PIN PB14 // SPI2_MISO - #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI + #define TOUCH_CS_PIN PA7 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 // SPI2_SCK + #define TOUCH_MISO_PIN PB14 // SPI2_MISO + #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 9090fb34c4..b42856721d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -47,74 +47,74 @@ // // Servos // -#define SERVO0_PIN PA8 // BLTOUCH +#define SERVO0_PIN PA8 // BLTOUCH // // Limit Switches // -#define X_MIN_PIN PA15 -#define X_MAX_PIN PG7 -#define Y_MIN_PIN PA12 -#define Y_MAX_PIN PG8 -#define Z_MIN_PIN PA11 -#define Z_MAX_PIN PC4 +#define X_MIN_PIN PA15 +#define X_MAX_PIN PG7 +#define Y_MIN_PIN PA12 +#define Y_MAX_PIN PG8 +#define Z_MIN_PIN PA11 +#define Z_MAX_PIN PC4 // // Steppers // -#define X_ENABLE_PIN PE4 -#define X_STEP_PIN PE3 -#define X_DIR_PIN PE2 +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 #ifndef X_CS_PIN - #define X_CS_PIN PF8 + #define X_CS_PIN PF8 #endif -#define Y_ENABLE_PIN PE1 -#define Y_STEP_PIN PE0 -#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 #ifndef Y_CS_PIN - #define Y_CS_PIN PF3 + #define Y_CS_PIN PF3 #endif -#define Z_ENABLE_PIN PB8 -#define Z_STEP_PIN PB5 -#define Z_DIR_PIN PB4 +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 #ifndef Z_CS_PIN - #define Z_CS_PIN PF6 + #define Z_CS_PIN PF6 #endif -#define E0_ENABLE_PIN PB3 -#define E0_STEP_PIN PD6 -#define E0_DIR_PIN PD3 +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 #ifndef E0_CS_PIN - #define E0_CS_PIN PG15 + #define E0_CS_PIN PG15 #endif -#define E1_ENABLE_PIN PA3 -#define E1_STEP_PIN PA6 -#define E1_DIR_PIN PA1 +#define E1_ENABLE_PIN PA3 +#define E1_STEP_PIN PA6 +#define E1_DIR_PIN PA1 #ifndef E1_CS_PIN - #define E1_CS_PIN PG10 + #define E1_CS_PIN PG10 #endif -#define E2_ENABLE_PIN PF0 -#define E2_STEP_PIN PF2 -#define E2_DIR_PIN PF1 +#define E2_ENABLE_PIN PF0 +#define E2_STEP_PIN PF2 +#define E2_DIR_PIN PF1 #ifndef E2_CS_PIN - #define E2_CS_PIN PG9 + #define E2_CS_PIN PG9 #endif // // Software SPI pins for TMC2130 stepper drivers // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 + #define TMC_SW_MOSI PB15 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 + #define TMC_SW_MISO PB14 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 + #define TMC_SW_SCK PB13 #endif #endif @@ -140,71 +140,71 @@ // // Software serial // - #define X_SERIAL_TX_PIN PF7 - #define X_SERIAL_RX_PIN PF8 + #define X_SERIAL_TX_PIN PF7 + #define X_SERIAL_RX_PIN PF8 - #define Y_SERIAL_TX_PIN PF4 - #define Y_SERIAL_RX_PIN PF3 + #define Y_SERIAL_TX_PIN PF4 + #define Y_SERIAL_RX_PIN PF3 - #define Z_SERIAL_TX_PIN PF5 - #define Z_SERIAL_RX_PIN PF6 + #define Z_SERIAL_TX_PIN PF5 + #define Z_SERIAL_RX_PIN PF6 - #define E0_SERIAL_TX_PIN PG13 - #define E0_SERIAL_RX_PIN PG15 + #define E0_SERIAL_TX_PIN PG13 + #define E0_SERIAL_RX_PIN PG15 - #define E1_SERIAL_TX_PIN PG12 - #define E1_SERIAL_RX_PIN PG10 + #define E1_SERIAL_TX_PIN PG12 + #define E1_SERIAL_RX_PIN PG10 - #define E2_SERIAL_TX_PIN PC13 - #define E2_SERIAL_RX_PIN PG9 + #define E2_SERIAL_TX_PIN PC13 + #define E2_SERIAL_RX_PIN PG9 #endif // // Temperature Sensors // -#define TEMP_0_PIN PC1 // TH1 -#define TEMP_1_PIN PC2 // TH2 -#define TEMP_2_PIN PC3 // TH3 -#define TEMP_BED_PIN PC0 // TB1 +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PC2 // TH2 +#define TEMP_2_PIN PC3 // TH3 +#define TEMP_BED_PIN PC0 // TB1 // // Heaters / Fans // -#define HEATER_0_PIN PF10 // +HE0- -#define HEATER_1_PIN PB0 // +HE1- -#define HEATER_2_PIN PF9 // +HE2- -#define HEATER_BED_PIN PA0 // +HOT-BED- -#define FAN_PIN PB1 // +FAN- +#define HEATER_0_PIN PF10 // +HE0- +#define HEATER_1_PIN PB0 // +HE1- +#define HEATER_2_PIN PF9 // +HE2- +#define HEATER_BED_PIN PA0 // +HOT-BED- +#define FAN_PIN PB1 // +FAN- /** * Note: MKS Robin Pro board is using SPI2 interface. Make sure your stm32duino library is configured accordingly */ -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PF11 // TC2 - CS2 +//#define MAX6675_SS_PIN PE5 // TC1 - CS1 +//#define MAX6675_SS_PIN PF11 // TC2 - CS2 -#define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PG11 // PW_OFF -#define FIL_RUNOUT_PIN PA4 // MT_DET1 -//#define FIL_RUNOUT_PIN PE6 // MT_DET2 -//#define FIL_RUNOUT_PIN PG14 // MT_DET3 +#define POWER_LOSS_PIN PA2 // PW_DET +#define PS_ON_PIN PG11 // PW_OFF +#define FIL_RUNOUT_PIN PA4 // MT_DET1 +//#define FIL_RUNOUT_PIN PE6 // MT_DET2 +//#define FIL_RUNOUT_PIN PG14 // MT_DET3 // // SD Card // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(LCD) #define ENABLE_SPI2 - #define SD_DETECT_PIN PG3 - #define SCK_PIN PB13 - #define MISO_PIN PB14 - #define MOSI_PIN PB15 - #define SS_PIN PG6 + #define SD_DETECT_PIN PG3 + #define SCK_PIN PB13 + #define MISO_PIN PB14 + #define MOSI_PIN PB15 + #define SS_PIN PG6 #elif SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT - #define SD_DETECT_PIN PD12 + #define SD_DETECT_PIN PD12 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif @@ -215,60 +215,60 @@ * to let the bootloader init the screen. */ #if ENABLED(FSMC_GRAPHICAL_TFT) - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 - #define LCD_RESET_PIN PF6 - #define NO_LCD_REINIT // Suppress LCD re-initialization + #define LCD_RESET_PIN PF6 + #define NO_LCD_REINIT // Suppress LCD re-initialization - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_BACKLIGHT_PIN PD13 #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PA7 + #define TOUCH_CS_PIN PA7 #else - #define BEEPER_PIN PC5 - #define BTN_ENC PG2 - #define BTN_EN1 PG5 - #define BTN_EN2 PG4 + #define BEEPER_PIN PC5 + #define BTN_ENC PG2 + #define BTN_EN1 PG5 + #define BTN_EN2 PG4 #endif #elif HAS_SPI_LCD - #define BEEPER_PIN PC5 - #define BTN_ENC PG2 - #define LCD_PINS_ENABLE PG0 - #define LCD_PINS_RS PG1 - #define BTN_EN1 PG5 - #define BTN_EN2 PG4 + #define BEEPER_PIN PC5 + #define BTN_ENC PG2 + #define LCD_PINS_ENABLE PG0 + #define LCD_PINS_RS PG1 + #define BTN_EN1 PG5 + #define BTN_EN2 PG4 // MKS MINI12864 and MKS LCD12864B. If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) - #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PF12 - #define DOGLCD_CS PF15 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 PF12 + #define DOGLCD_CS PF15 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 - #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY - #define LCD_PINS_D4 PF14 + #define LCD_PINS_D4 PF14 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PF15 - #define LCD_PINS_D6 PF12 - #define LCD_PINS_D7 PF13 + #define LCD_PINS_D5 PF15 + #define LCD_PINS_D6 PF12 + #define LCD_PINS_D7 PF13 #endif #endif // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY #endif #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(125) + #define ST7920_DELAY_1 DELAY_NS(125) #endif #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(125) + #define ST7920_DELAY_2 DELAY_NS(125) #endif #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(125) + #define ST7920_DELAY_3 DELAY_NS(125) #endif diff --git a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h index 8c583434e4..7311d91a80 100644 --- a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h +++ b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h @@ -39,53 +39,53 @@ // // Limit Switches // -#define X_MIN_PIN PB14 -#define Y_MIN_PIN PB13 -#define Z_MIN_PIN PB12 +#define X_MIN_PIN PB14 +#define Y_MIN_PIN PB13 +#define Z_MIN_PIN PB12 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB9 + #define Z_MIN_PROBE_PIN PB9 #endif // // Steppers // // X & Y enable are the same -#define X_STEP_PIN PB7 -#define X_DIR_PIN PB6 -#define X_ENABLE_PIN PB8 +#define X_STEP_PIN PB7 +#define X_DIR_PIN PB6 +#define X_ENABLE_PIN PB8 -#define Y_STEP_PIN PB5 -#define Y_DIR_PIN PB4 -#define Y_ENABLE_PIN PB8 +#define Y_STEP_PIN PB5 +#define Y_DIR_PIN PB4 +#define Y_ENABLE_PIN PB8 -#define Z_STEP_PIN PA15 -#define Z_DIR_PIN PA10 -#define Z_ENABLE_PIN PB3 +#define Z_STEP_PIN PA15 +#define Z_DIR_PIN PA10 +#define Z_ENABLE_PIN PB3 -#define E0_STEP_PIN PA8 -#define E0_DIR_PIN PB15 -#define E0_ENABLE_PIN PA9 +#define E0_STEP_PIN PA8 +#define E0_DIR_PIN PB15 +#define E0_ENABLE_PIN PA9 // // Temperature Sensors // -#define TEMP_0_PIN PB1 // Analog Input (HOTEND thermistor) -#define TEMP_BED_PIN PB0 // Analog Input (BED thermistor) +#define TEMP_0_PIN PB1 // Analog Input (HOTEND thermistor) +#define TEMP_BED_PIN PB0 // Analog Input (BED thermistor) // // Heaters / Fans // -#define HEATER_0_PIN PA2 // HOTEND MOSFET -#define HEATER_BED_PIN PA0 // BED MOSFET +#define HEATER_0_PIN PA2 // HOTEND MOSFET +#define HEATER_BED_PIN PA0 // BED MOSFET -#define FAN_PIN PA1 // FAN1 header on board - PRINT FAN +#define FAN_PIN PA1 // FAN1 header on board - PRINT FAN // // Misc. // -#define LED_PIN PC13 -#define SDSS PA3 +#define LED_PIN PC13 +#define SDSS PA3 diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index b43492af21..d144c0e692 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -38,61 +38,61 @@ // // Limit Switches // -#define X_STOP_PIN PB3 -#define Y_STOP_PIN PB4 -#define Z_STOP_PIN PB5 +#define X_STOP_PIN PB3 +#define Y_STOP_PIN PB4 +#define Z_STOP_PIN PB5 // // Steppers // -#define X_STEP_PIN PC0 -#define X_DIR_PIN PC1 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PC0 +#define X_DIR_PIN PC1 +#define X_ENABLE_PIN PA8 -#define Y_STEP_PIN PC2 -#define Y_DIR_PIN PC3 -#define Y_ENABLE_PIN PA8 +#define Y_STEP_PIN PC2 +#define Y_DIR_PIN PC3 +#define Y_ENABLE_PIN PA8 -#define Z_STEP_PIN PC4 -#define Z_DIR_PIN PC5 -#define Z_ENABLE_PIN PA8 +#define Z_STEP_PIN PC4 +#define Z_DIR_PIN PC5 +#define Z_ENABLE_PIN PA8 -#define E0_STEP_PIN PC6 -#define E0_DIR_PIN PC7 -#define E0_ENABLE_PIN PA8 +#define E0_STEP_PIN PC6 +#define E0_DIR_PIN PC7 +#define E0_ENABLE_PIN PA8 /** * TODO: Currently using same Enable pin to all steppers. */ -#define E1_STEP_PIN PC8 -#define E1_DIR_PIN PC9 -#define E1_ENABLE_PIN PA8 +#define E1_STEP_PIN PC8 +#define E1_DIR_PIN PC9 +#define E1_ENABLE_PIN PA8 -#define E2_STEP_PIN PC10 -#define E2_DIR_PIN PC11 -#define E2_ENABLE_PIN PA8 +#define E2_STEP_PIN PC10 +#define E2_DIR_PIN PC11 +#define E2_ENABLE_PIN PA8 // // Misc. Functions // -#define SDSS PA4 -#define LED_PIN PD2 +#define SDSS PA4 +#define LED_PIN PD2 // // Heaters / Fans // -#define HEATER_0_PIN PB0 // EXTRUDER 1 -#define HEATER_1_PIN PB1 +#define HEATER_0_PIN PB0 // EXTRUDER 1 +#define HEATER_1_PIN PB1 -#define HEATER_BED_PIN PA3 // BED +#define HEATER_BED_PIN PA3 // BED // // Temperature Sensors // -#define TEMP_BED_PIN PA0 // Analog Input -#define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN PA2 // Analog Input +#define TEMP_BED_PIN PA0 // Analog Input +#define TEMP_0_PIN PA1 // Analog Input +#define TEMP_1_PIN PA2 // Analog Input // // LCD Pins @@ -100,25 +100,25 @@ #if HAS_SPI_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #else - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons attached to a shift register // Not wired yet //#define SHIFT_CLK 38 @@ -132,14 +132,14 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) #define LCD_BACKLIGHT_PIN 39 @@ -147,112 +147,112 @@ #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS 53 + #define SD_DETECT_PIN -1 + #define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define BTN_ENC -1 + #define LCD_SDSS 53 + #define SD_DETECT_PIN 49 #elif ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 + #define DOGLCD_A0 44 + #define DOGLCD_CS 45 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board + #define SDSS 53 + #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 31 + #define KILL_PIN 31 - #define STAT_LED_RED_PIN 32 + #define STAT_LED_RED_PIN 32 #define STAT_LED_BLUE_PIN 35 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 + #define SD_DETECT_PIN 49 + #define LCD_SDSS 53 + #define KILL_PIN 41 + #define BEEPER_PIN 23 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 #define LCD_BACKLIGHT_PIN 33 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define SDSS 53 - #define KILL_PIN 64 + #define KILL_PIN 64 // GLCD features // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 // not connected to a pin - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this + //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index 99f1cea35c..58b13b90df 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -41,72 +41,72 @@ // // Limit Switches // -#define X_STOP_PIN PD0 -#define Y_STOP_PIN PD1 -#define Z_STOP_PIN PD4 +#define X_STOP_PIN PD0 +#define Y_STOP_PIN PD1 +#define Z_STOP_PIN PD4 // // Steppers // -#define X_STEP_PIN PE1 -#define X_DIR_PIN PE0 -#define X_ENABLE_PIN PC0 +#define X_STEP_PIN PE1 +#define X_DIR_PIN PE0 +#define X_ENABLE_PIN PC0 -#define Y_STEP_PIN PE3 -#define Y_DIR_PIN PE2 -#define Y_ENABLE_PIN PC1 +#define Y_STEP_PIN PE3 +#define Y_DIR_PIN PE2 +#define Y_ENABLE_PIN PC1 -#define Z_STEP_PIN PE5 -#define Z_DIR_PIN PE4 -#define Z_ENABLE_PIN PC2 +#define Z_STEP_PIN PE5 +#define Z_DIR_PIN PE4 +#define Z_ENABLE_PIN PC2 -#define E0_STEP_PIN PE7 -#define E0_DIR_PIN PE6 -#define E0_ENABLE_PIN PC3 +#define E0_STEP_PIN PE7 +#define E0_DIR_PIN PE6 +#define E0_ENABLE_PIN PC3 -#define E1_STEP_PIN PE9 -#define E1_DIR_PIN PE8 -#define E1_ENABLE_PIN PC4 +#define E1_STEP_PIN PE9 +#define E1_DIR_PIN PE8 +#define E1_ENABLE_PIN PC4 -#define E2_STEP_PIN PE11 -#define E2_DIR_PIN PE10 -#define E2_ENABLE_PIN PC5 +#define E2_STEP_PIN PE11 +#define E2_DIR_PIN PE10 +#define E2_ENABLE_PIN PC5 // // Misc. Functions // -#define SDSS PA15 -#define LED_PIN PB2 +#define SDSS PA15 +#define LED_PIN PB2 // // Heaters / Fans // -#define HEATER_0_PIN PD12 // EXTRUDER 1 -//#define HEATER_1_PIN PD13 +#define HEATER_0_PIN PD12 // EXTRUDER 1 +//#define HEATER_1_PIN PD13 -#define HEATER_BED_PIN PB9 // BED -//#define HEATER_BED2_PIN -1 // BED2 -//#define HEATER_BED3_PIN -1 // BED3 +#define HEATER_BED_PIN PB9 // BED +//#define HEATER_BED2_PIN -1 // BED2 +//#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN - #define FAN_PIN PD14 + #define FAN_PIN PD14 #endif -#define FAN1_PIN PD13 +#define FAN1_PIN PD13 #define FAN_SOFT_PWM // // Temperature Sensors // -#define TEMP_BED_PIN PA0 -#define TEMP_0_PIN PA1 -#define TEMP_1_PIN PA2 -#define TEMP_2_PIN PA3 +#define TEMP_BED_PIN PA0 +#define TEMP_0_PIN PA1 +#define TEMP_1_PIN PA2 +#define TEMP_2_PIN PA3 // Laser control #if HAS_CUTTER - #define SPINDLE_LASER_PWM_PIN PB8 - #define SPINDLE_LASER_ENA_PIN PD5 + #define SPINDLE_LASER_PWM_PIN PB8 + #define SPINDLE_LASER_ENA_PIN PD5 #endif // @@ -115,54 +115,54 @@ #if HAS_SPI_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #else - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK 38 - //#define SHIFT_LD 42 - //#define SHIFT_OUT 40 - //#define SHIFT_EN 17 + //#define SHIFT_CLK 38 + //#define SHIFT_LD 42 + //#define SHIFT_OUT 40 + //#define SHIFT_EN 17 #endif #endif #if ENABLED(TOUCH_BUTTONS) - #define TOUCH_CS_PIN PB12 // SPI2_NSS - #define TOUCH_SCK_PIN PB13 - #define TOUCH_MOSI_PIN PB14 - #define TOUCH_MISO_PIN PB15 - #define TOUCH_INT_PIN PC6 // (PenIRQ coming from ADS7843) + #define TOUCH_CS_PIN PB12 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 + #define TOUCH_MOSI_PIN PB14 + #define TOUCH_MISO_PIN PB15 + #define TOUCH_INT_PIN PC6 // (PenIRQ coming from ADS7843) #elif ENABLED(NEWPANEL) #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) #define LCD_BACKLIGHT_PIN 39 @@ -170,113 +170,113 @@ #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 #define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS 53 + #define SD_DETECT_PIN -1 + #define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 - #define LCD_SDSS 53 + #define BTN_ENC -1 + #define LCD_SDSS 53 #define SD_DETECT_PIN 49 #elif ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 + #define DOGLCD_A0 44 + #define DOGLCD_CS 45 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board + #define SDSS 53 + #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 31 + #define KILL_PIN 31 - #define STAT_LED_RED_PIN 32 + #define STAT_LED_RED_PIN 32 #define STAT_LED_BLUE_PIN 35 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define LCD_SDSS 53 + #define KILL_PIN 41 + #define BEEPER_PIN 23 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 #define LCD_BACKLIGHT_PIN 33 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define SDSS 53 - #define KILL_PIN 64 + #define KILL_PIN 64 // GLCD features // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 // not connected to a pin #define SD_DETECT_PIN 49 #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define KILL_PIN 41 #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this + //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index 1e33336512..ddbe09c355 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -34,21 +34,21 @@ #define ARMED_V1_1 #endif -#undef BOARD_INFO_NAME // Defined on the command line by Arduino Core STM32 +#undef BOARD_INFO_NAME // Defined on the command line by Arduino Core STM32 #define BOARD_INFO_NAME "Arm'ed" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #define I2C_EEPROM -#undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. -#define E2END 0xFFF // 4KB +#undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. +#define E2END 0xFFF // 4KB // // Limit Switches // -#define X_STOP_PIN PE0 -#define Y_STOP_PIN PE1 -#define Z_STOP_PIN PE14 +#define X_STOP_PIN PE0 +#define Y_STOP_PIN PE1 +#define Z_STOP_PIN PE14 // // Z Probe (when not Z_MIN_PIN) @@ -61,7 +61,7 @@ // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA3 + #define FIL_RUNOUT_PIN PA3 #endif // @@ -69,163 +69,163 @@ // #ifdef ARMED_SWAP_X_E1 - #define X_STEP_PIN PE4 - #define X_DIR_PIN PE2 - #define X_ENABLE_PIN PE3 - #define X_CS_PIN PE5 + #define X_STEP_PIN PE4 + #define X_DIR_PIN PE2 + #define X_ENABLE_PIN PE3 + #define X_CS_PIN PE5 #else - #define X_STEP_PIN PD3 - #define X_DIR_PIN PD2 - #define X_ENABLE_PIN PD0 - #define X_CS_PIN PD1 + #define X_STEP_PIN PD3 + #define X_DIR_PIN PD2 + #define X_ENABLE_PIN PD0 + #define X_CS_PIN PD1 #endif -#define Y_STEP_PIN PE11 -#define Y_DIR_PIN PE10 -#define Y_ENABLE_PIN PE13 -#define Y_CS_PIN PE12 +#define Y_STEP_PIN PE11 +#define Y_DIR_PIN PE10 +#define Y_ENABLE_PIN PE13 +#define Y_CS_PIN PE12 -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD7 -#define Z_ENABLE_PIN PD4 -#define Z_CS_PIN PD5 +#define Z_STEP_PIN PD6 +#define Z_DIR_PIN PD7 +#define Z_ENABLE_PIN PD4 +#define Z_CS_PIN PD5 -#define E0_STEP_PIN PB5 -#define E0_DIR_PIN PB6 +#define E0_STEP_PIN PB5 +#define E0_DIR_PIN PB6 #ifdef ARMED_V1_1 - #define E0_ENABLE_PIN PC12 + #define E0_ENABLE_PIN PC12 #else - #define E0_ENABLE_PIN PB3 + #define E0_ENABLE_PIN PB3 #endif -#define E0_CS_PIN PB4 +#define E0_CS_PIN PB4 #ifdef ARMED_SWAP_X_E1 - #define E1_STEP_PIN PD3 - #define E1_DIR_PIN PD2 - #define E1_ENABLE_PIN PD0 - #define E1_CS_PIN PD1 + #define E1_STEP_PIN PD3 + #define E1_DIR_PIN PD2 + #define E1_ENABLE_PIN PD0 + #define E1_CS_PIN PD1 #else - #define E1_STEP_PIN PE4 - #define E1_DIR_PIN PE2 - #define E1_ENABLE_PIN PE3 - #define E1_CS_PIN PE5 + #define E1_STEP_PIN PE4 + #define E1_DIR_PIN PE2 + #define E1_ENABLE_PIN PE3 + #define E1_CS_PIN PE5 #endif // // Temperature Sensors // -#define TEMP_0_PIN PC0 // Analog Input -#define TEMP_1_PIN PC1 // Analog Input -#define TEMP_BED_PIN PC2 // Analog Input +#define TEMP_0_PIN PC0 // Analog Input +#define TEMP_1_PIN PC1 // Analog Input +#define TEMP_BED_PIN PC2 // Analog Input #if HOTENDS == 1 && TEMP_SENSOR_PROBE - #define TEMP_PROBE_PIN PC1 + #define TEMP_PROBE_PIN PC1 #endif // // Heaters / Fans // -#define HEATER_0_PIN PA1 // Hardware PWM -#define HEATER_1_PIN PA2 // Hardware PWM -#define HEATER_BED_PIN PA0 // Hardware PWM +#define HEATER_0_PIN PA1 // Hardware PWM +#define HEATER_1_PIN PA2 // Hardware PWM +#define HEATER_BED_PIN PA0 // Hardware PWM -#define FAN_PIN PC6 // Hardware PWM, Part cooling fan -#define FAN1_PIN PC7 // Hardware PWM, Extruder fan -#define FAN2_PIN PC8 // Hardware PWM, Controller fan +#define FAN_PIN PC6 // Hardware PWM, Part cooling fan +#define FAN1_PIN PC7 // Hardware PWM, Extruder fan +#define FAN2_PIN PC8 // Hardware PWM, Controller fan // // Misc functions // -#define SDSS PE7 -#define LED_PIN PB7 // Heart beat -#define PS_ON_PIN PA10 -#define KILL_PIN PA8 -#define PWR_LOSS PA4 // Power loss / nAC_FAULT +#define SDSS PE7 +#define LED_PIN PB7 // Heart beat +#define PS_ON_PIN PA10 +#define KILL_PIN PA8 +#define PWR_LOSS PA4 // Power loss / nAC_FAULT // // LCD / Controller // -#define SD_DETECT_PIN PA15 -#define BEEPER_PIN PC9 +#define SD_DETECT_PIN PA15 +#define BEEPER_PIN PC9 #if ENABLED(FYSETC_MINI_12864) // // See https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 // - #define DOGLCD_A0 PE9 - #define DOGLCD_CS PE8 + #define DOGLCD_A0 PE9 + #define DOGLCD_CS PE8 - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PB12 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN PB12 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB13 + #define RGB_LED_R_PIN PB13 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB14 + #define RGB_LED_G_PIN PB14 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB15 + #define RGB_LED_B_PIN PB15 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PB13 + #define NEOPIXEL_PIN PB13 #endif #else - #define LCD_PINS_RS PE9 - #define LCD_PINS_ENABLE PE8 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PE9 + #define LCD_PINS_ENABLE PE8 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS PB13 - #define DOGLCD_A0 PB14 + #define DOGLCD_CS PB13 + #define DOGLCD_A0 PB14 #endif #endif -#define BTN_EN1 PC4 -#define BTN_EN2 PC5 -#define BTN_ENC PC3 +#define BTN_EN1 PC4 +#define BTN_EN2 PC5 +#define BTN_ENC PC3 // // Extension pins // -#define EXT0_PIN PB0 -#define EXT1_PIN PB1 -#define EXT2_PIN PB2 -#define EXT3_PIN PD8 -#define EXT4_PIN PD9 -#define EXT5_PIN PD10 -#define EXT6_PIN PD11 -#define EXT7_PIN PD12 -#define EXT8_PIN PB10 -#define EXT9_PIN PB11 +#define EXT0_PIN PB0 +#define EXT1_PIN PB1 +#define EXT2_PIN PB2 +#define EXT3_PIN PD8 +#define EXT4_PIN PD9 +#define EXT5_PIN PD10 +#define EXT6_PIN PD11 +#define EXT7_PIN PD12 +#define EXT8_PIN PB10 +#define EXT9_PIN PB11 #if HAS_TMC_UART // TMC2208/TMC2209 stepper drivers // // Software serial // - #define X_SERIAL_TX_PIN EXT0_PIN - #define X_SERIAL_RX_PIN EXT0_PIN + #define X_SERIAL_TX_PIN EXT0_PIN + #define X_SERIAL_RX_PIN EXT0_PIN - #define Y_SERIAL_TX_PIN EXT1_PIN - #define Y_SERIAL_RX_PIN EXT1_PIN + #define Y_SERIAL_TX_PIN EXT1_PIN + #define Y_SERIAL_RX_PIN EXT1_PIN - #define Z_SERIAL_TX_PIN EXT2_PIN - #define Z_SERIAL_RX_PIN EXT2_PIN + #define Z_SERIAL_TX_PIN EXT2_PIN + #define Z_SERIAL_RX_PIN EXT2_PIN - #define E0_SERIAL_TX_PIN EXT3_PIN - #define E0_SERIAL_RX_PIN EXT3_PIN + #define E0_SERIAL_TX_PIN EXT3_PIN + #define E0_SERIAL_RX_PIN EXT3_PIN - #define E1_SERIAL_RX_PIN EXT4_PIN - #define E1_SERIAL_TX_PIN EXT4_PIN + #define E1_SERIAL_RX_PIN EXT4_PIN + #define E1_SERIAL_TX_PIN EXT4_PIN - #define Z2_SERIAL_RX_PIN EXT4_PIN - #define Z2_SERIAL_TX_PIN EXT4_PIN + #define Z2_SERIAL_RX_PIN EXT4_PIN + #define Z2_SERIAL_TX_PIN EXT4_PIN #define TMC_BAUD_RATE 19200 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BEAST.h b/Marlin/src/pins/stm32f4/pins_BEAST.h index d779994d19..5be4368789 100644 --- a/Marlin/src/pins/stm32f4/pins_BEAST.h +++ b/Marlin/src/pins/stm32f4/pins_BEAST.h @@ -41,70 +41,70 @@ // // Steppers // -#define X_STEP_PIN PE0 -#define X_DIR_PIN PE1 -#define X_ENABLE_PIN PC0 -#define X_MIN_PIN PD5 -#define X_MAX_PIN -1 +#define X_STEP_PIN PE0 +#define X_DIR_PIN PE1 +#define X_ENABLE_PIN PC0 +#define X_MIN_PIN PD5 +#define X_MAX_PIN -1 -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 -#define Y_ENABLE_PIN PC1 -#define Y_MIN_PIN PD6 +#define Y_STEP_PIN PE2 +#define Y_DIR_PIN PE3 +#define Y_ENABLE_PIN PC1 +#define Y_MIN_PIN PD6 #define Y_MAX_PIN -#define Z_STEP_PIN PE4 -#define Z_DIR_PIN PE5 -#define Z_ENABLE_PIN PC2 -#define Z_MIN_PIN PD7 -#define Z_MAX_PIN -1 +#define Z_STEP_PIN PE4 +#define Z_DIR_PIN PE5 +#define Z_ENABLE_PIN PC2 +#define Z_MIN_PIN PD7 +#define Z_MAX_PIN -1 -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 +#define Y2_STEP_PIN -1 +#define Y2_DIR_PIN -1 +#define Y2_ENABLE_PIN -1 -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 +#define Z2_STEP_PIN -1 +#define Z2_DIR_PIN -1 +#define Z2_ENABLE_PIN -1 -#define E0_STEP_PIN PE6 -#define E0_DIR_PIN PE7 -#define E0_ENABLE_PIN PC3 +#define E0_STEP_PIN PE6 +#define E0_DIR_PIN PE7 +#define E0_ENABLE_PIN PC3 /** * TODO: Currently using same Enable pin to all steppers. */ -#define E1_STEP_PIN PE8 -#define E1_DIR_PIN PE9 -#define E1_ENABLE_PIN PC4 +#define E1_STEP_PIN PE8 +#define E1_DIR_PIN PE9 +#define E1_ENABLE_PIN PC4 -#define E2_STEP_PIN PE10 -#define E2_DIR_PIN PE11 -#define E2_ENABLE_PIN PC5 +#define E2_STEP_PIN PE10 +#define E2_DIR_PIN PE11 +#define E2_ENABLE_PIN PC5 // // Misc. Functions // -#define SDSS PA15 -#define LED_PIN PB2 +#define SDSS PA15 +#define LED_PIN PB2 -#define PS_ON_PIN -1 -#define KILL_PIN -1 +#define PS_ON_PIN -1 +#define KILL_PIN -1 // // Heaters / Fans // -#define HEATER_0_PIN PD12 // EXTRUDER 1 -#define HEATER_1_PIN PD13 -#define HEATER_2_PIN PD14 +#define HEATER_0_PIN PD12 // EXTRUDER 1 +#define HEATER_1_PIN PD13 +#define HEATER_2_PIN PD14 -#define HEATER_BED_PIN PB9 // BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 +#define HEATER_BED_PIN PB9 // BED +#define HEATER_BED2_PIN -1 // BED2 +#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN - #define FAN_PIN PB10 + #define FAN_PIN PB10 #endif #define FAN_SOFT_PWM @@ -112,10 +112,10 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA0 // Analog Input -#define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN PA2 // Analog Input -#define TEMP_2_PIN PA3 // Analog Input +#define TEMP_BED_PIN PA0 // Analog Input +#define TEMP_0_PIN PA1 // Analog Input +#define TEMP_1_PIN PA2 // Analog Input +#define TEMP_2_PIN PA3 // Analog Input // // LCD Pins @@ -123,25 +123,25 @@ #if HAS_SPI_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #else - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 - #define LCD_PINS_D4 PB12 - #define LCD_PINS_D5 PB13 - #define LCD_PINS_D6 PB14 - #define LCD_PINS_D7 PB15 + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_D4 PB12 + #define LCD_PINS_D5 PB13 + #define LCD_PINS_D6 PB14 + #define LCD_PINS_D7 PB15 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons attached to a shift register // Not wired yet //#define SHIFT_CLK 38 @@ -155,14 +155,14 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) #define LCD_BACKLIGHT_PIN 39 @@ -170,113 +170,113 @@ #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS 53 + #define SD_DETECT_PIN -1 + #define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define BTN_ENC -1 + #define LCD_SDSS 53 + #define SD_DETECT_PIN 49 #elif ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 + #define DOGLCD_A0 44 + #define DOGLCD_CS 45 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board + #define SDSS 53 + #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 31 + #define KILL_PIN 31 - #define STAT_LED_RED_PIN 32 + #define STAT_LED_RED_PIN 32 #define STAT_LED_BLUE_PIN 35 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 + #define SD_DETECT_PIN 49 + #define LCD_SDSS 53 + #define KILL_PIN 41 + #define BEEPER_PIN 23 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 #define LCD_BACKLIGHT_PIN 33 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define SDSS 53 - #define KILL_PIN 64 + #define KILL_PIN 64 // GLCD features // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 // not connected to a pin - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #else - //#define SD_DETECT_PIN -1 // Ramps doesn't use this + //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index d0edf897f4..170b90368b 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -40,116 +40,116 @@ #define DEFAULT_MACHINE_NAME "STM32F407VET6" //#define I2C_EEPROM -//#define E2END 0x1FFF // 8KB +//#define E2END 0x1FFF // 8KB #define SRAM_EEPROM_EMULATION // // Servos // -#define SERVO0_PIN PC6 -#define SERVO1_PIN PC7 +#define SERVO0_PIN PC6 +#define SERVO1_PIN PC7 // // Limit Switches // -#define X_MIN_PIN PC13 -#define X_MAX_PIN PA15 -#define Y_MIN_PIN PA5 -#define Y_MAX_PIN PD12 -#define Z_MIN_PIN PD14 -#define Z_MAX_PIN PD15 +#define X_MIN_PIN PC13 +#define X_MAX_PIN PA15 +#define Y_MIN_PIN PA5 +#define Y_MAX_PIN PD12 +#define Z_MIN_PIN PD14 +#define Z_MAX_PIN PD15 // // Steppers // -#define X_STEP_PIN PC4 -#define X_DIR_PIN PA4 -#define X_ENABLE_PIN PE7 +#define X_STEP_PIN PC4 +#define X_DIR_PIN PA4 +#define X_ENABLE_PIN PE7 -#define Y_STEP_PIN PE5 -#define Y_DIR_PIN PE2 -#define Y_ENABLE_PIN PE6 +#define Y_STEP_PIN PE5 +#define Y_DIR_PIN PE2 +#define Y_ENABLE_PIN PE6 -#define Z_STEP_PIN PD5 -#define Z_DIR_PIN PD3 -#define Z_ENABLE_PIN PD6 +#define Z_STEP_PIN PD5 +#define Z_DIR_PIN PD3 +#define Z_ENABLE_PIN PD6 -#define E0_STEP_PIN PD7 -#define E0_DIR_PIN PD0 -#define E0_ENABLE_PIN PB9 +#define E0_STEP_PIN PD7 +#define E0_DIR_PIN PD0 +#define E0_ENABLE_PIN PB9 -#define E1_STEP_PIN PE0 -#define E1_DIR_PIN PE1 -#define E1_ENABLE_PIN PB8 +#define E1_STEP_PIN PE0 +#define E1_DIR_PIN PE1 +#define E1_ENABLE_PIN PB8 // // Temperature Sensors // -#define TEMP_0_PIN PC0 // T0 -#define TEMP_1_PIN PC1 // T1 -#define TEMP_BED_PIN PC2 // TB +#define TEMP_0_PIN PC0 // T0 +#define TEMP_1_PIN PC1 // T1 +#define TEMP_BED_PIN PC2 // TB #ifndef TEMP_CHAMBER_PIN - #define TEMP_CHAMBER_PIN PC3 // TC + #define TEMP_CHAMBER_PIN PC3 // TC #endif // // Heaters / Fans // -#define HEATER_0_PIN PA2 // Heater0 -#define HEATER_1_PIN PA3 // Heater1 -#define HEATER_BED_PIN PA1 // Hotbed +#define HEATER_0_PIN PA2 // Heater0 +#define HEATER_1_PIN PA3 // Heater1 +#define HEATER_BED_PIN PA1 // Hotbed -#define FAN_PIN PE9 // Fan0 -#define FAN1_PIN PE11 // Fan1 -#define FAN2_PIN PE13 // Fan2 -#define FAN3_PIN PE14 // Fan3 +#define FAN_PIN PE9 // Fan0 +#define FAN1_PIN PE11 // Fan1 +#define FAN2_PIN PE13 // Fan2 +#define FAN3_PIN PE14 // Fan3 // // Misc. Functions // -#define LED_PIN PA6 -//#define LED_PIN PA7 -#define KILL_PIN PB1 +#define LED_PIN PA6 +//#define LED_PIN PA7 +#define KILL_PIN PB1 // // LCD / Controller // -//#define SD_DETECT_PIN PC5 -//#define SD_DETECT_PIN PA8 // SDIO SD_DETECT_PIN, external SDIO card reader only +//#define SD_DETECT_PIN PC5 +//#define SD_DETECT_PIN PA8 // SDIO SD_DETECT_PIN, external SDIO card reader only -#define BEEPER_PIN PD10 -#define LCD_PINS_RS PE15 -#define LCD_PINS_ENABLE PD8 -#define LCD_PINS_D4 PE10 -#define LCD_PINS_D5 PE12 -#define LCD_PINS_D6 PD1 -#define LCD_PINS_D7 PE8 -#define BTN_ENC PD9 -#define BTN_EN1 PD4 -#define BTN_EN2 PD13 +#define BEEPER_PIN PD10 +#define LCD_PINS_RS PE15 +#define LCD_PINS_ENABLE PD8 +#define LCD_PINS_D4 PE10 +#define LCD_PINS_D5 PE12 +#define LCD_PINS_D6 PD1 +#define LCD_PINS_D7 PE8 +#define BTN_ENC PD9 +#define BTN_EN1 PD4 +#define BTN_EN2 PD13 -#define DOGLCD_CS LCD_PINS_D5 -#define DOGLCD_A0 LCD_PINS_D6 +#define DOGLCD_CS LCD_PINS_D5 +#define DOGLCD_A0 LCD_PINS_D6 // // Onboard SD support // -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 #if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT - #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SCK_PIN SDIO_CK_PIN - #define MISO_PIN SDIO_D0_PIN - #define MOSI_PIN SDIO_CMD_PIN + #define SOFTWARE_SPI // Use soft SPI for onboard SD + #define SDSS SDIO_D3_PIN + #define SCK_PIN SDIO_CK_PIN + #define MISO_PIN SDIO_D0_PIN + #define MOSI_PIN SDIO_CMD_PIN #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 5d2c83e3b9..ee5c4da1fe 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -30,8 +30,8 @@ #define BOARD_INFO_NAME "BIGTREE Btt002 1.0" // Use one of these or SDCard-based Emulation will be used -//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation +#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 @@ -39,60 +39,60 @@ // // Limit Switches // -#define X_STOP_PIN PD3 -#define Y_STOP_PIN PD2 -#define Z_STOP_PIN PD1 // Shares J4 connector with PC3 +#define X_STOP_PIN PD3 +#define Y_STOP_PIN PD2 +#define Z_STOP_PIN PD1 // Shares J4 connector with PC3 // // Z Probe must be this pin // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PD1 + #define Z_MIN_PROBE_PIN PD1 #endif // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA15 + #define FIL_RUNOUT_PIN PA15 #endif // // Power Loss Detection // #ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PD4 + #define POWER_LOSS_PIN PD4 #endif // // Steppers // -#define X_STEP_PIN PA9 -#define X_DIR_PIN PA10 -#define X_ENABLE_PIN PA8 +#define X_STEP_PIN PA9 +#define X_DIR_PIN PA10 +#define X_ENABLE_PIN PA8 #ifndef X_CS_PIN - #define X_CS_PIN PE2 + #define X_CS_PIN PE2 #endif -#define Y_STEP_PIN PC8 -#define Y_DIR_PIN PC9 -#define Y_ENABLE_PIN PC7 +#define Y_STEP_PIN PC8 +#define Y_DIR_PIN PC9 +#define Y_ENABLE_PIN PC7 #ifndef Y_CS_PIN - #define Y_CS_PIN PE3 + #define Y_CS_PIN PE3 #endif -#define Z_STEP_PIN PD15 -#define Z_DIR_PIN PC6 -#define Z_ENABLE_PIN PD14 +#define Z_STEP_PIN PD15 +#define Z_DIR_PIN PC6 +#define Z_ENABLE_PIN PD14 #ifndef Z_CS_PIN - #define Z_CS_PIN PE4 + #define Z_CS_PIN PE4 #endif -#define E0_STEP_PIN PD12 -#define E0_DIR_PIN PD13 -#define E0_ENABLE_PIN PD11 +#define E0_STEP_PIN PD12 +#define E0_DIR_PIN PD13 +#define E0_ENABLE_PIN PD11 #ifndef E0_CS_PIN - #define E0_CS_PIN PD7 + #define E0_CS_PIN PD7 #endif // @@ -100,13 +100,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 + #define TMC_SW_MOSI PB15 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 + #define TMC_SW_MISO PB14 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 + #define TMC_SW_SCK PB13 #endif #endif @@ -132,17 +132,17 @@ // // Software serial ## // - #define X_SERIAL_TX_PIN PE2 - #define X_SERIAL_RX_PIN PE2 + #define X_SERIAL_TX_PIN PE2 + #define X_SERIAL_RX_PIN PE2 - #define Y_SERIAL_TX_PIN PE3 - #define Y_SERIAL_RX_PIN PE3 + #define Y_SERIAL_TX_PIN PE3 + #define Y_SERIAL_RX_PIN PE3 - #define Z_SERIAL_TX_PIN PE4 - #define Z_SERIAL_RX_PIN PE4 + #define Z_SERIAL_TX_PIN PE4 + #define Z_SERIAL_RX_PIN PE4 - #define E0_SERIAL_TX_PIN PD7 - #define E0_SERIAL_RX_PIN PD7 + #define E0_SERIAL_TX_PIN PD7 + #define E0_SERIAL_RX_PIN PD7 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -151,32 +151,32 @@ // // Temperature Sensors // -#define TEMP_0_PIN PA2 // T0 <-> E0 -#define TEMP_1_PIN PA0 // T1 <-> E1 -#define TEMP_BED_PIN PA1 // T2 <-> Bed -#define TEMP_PROBE_PIN PC3 // Shares J4 connector with PD1 +#define TEMP_0_PIN PA2 // T0 <-> E0 +#define TEMP_1_PIN PA0 // T1 <-> E1 +#define TEMP_BED_PIN PA1 // T2 <-> Bed +#define TEMP_PROBE_PIN PC3 // Shares J4 connector with PD1 // // Heaters / Fans // -#define HEATER_0_PIN PE6 // Heater0 -#define HEATER_BED_PIN PE5 // Hotbed -#define FAN_PIN PB8 // Fan1 -#define FAN1_PIN PB9 // Fan0 +#define HEATER_0_PIN PE6 // Heater0 +#define HEATER_BED_PIN PE5 // Hotbed +#define FAN_PIN PB8 // Fan1 +#define FAN1_PIN PB9 // Fan0 // HAL SPI1 pins #define CUSTOM_SPI_PINS #if ENABLED(CUSTOM_SPI_PINS) - #define SCK_PIN PA5 // SPI1 SCLK - #define SS_PIN PA4 // SPI1 SSEL - #define MISO_PIN PA6 // SPI1 MISO - #define MOSI_PIN PA7 // SPI1 MOSI + #define SCK_PIN PA5 // SPI1 SCLK + #define SS_PIN PA4 // SPI1 SSEL + #define MISO_PIN PA6 // SPI1 MISO + #define MOSI_PIN PA7 // SPI1 MOSI #endif // // Misc. Functions // -#define SDSS PA4 +#define SDSS PA4 /** * -------------------------------------BTT002 V1.0----------------------------------------------- @@ -194,35 +194,35 @@ // LCDs and Controllers // #if HAS_SPI_LCD - #define BEEPER_PIN PE7 - #define BTN_ENC PB1 + #define BEEPER_PIN PE7 + #define BTN_ENC PB1 #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PE12 + #define LCD_PINS_RS PE12 - #define BTN_EN1 PE9 - #define BTN_EN2 PE10 + #define BTN_EN1 PE9 + #define BTN_EN2 PE10 - #define LCD_PINS_ENABLE PE13 - #define LCD_PINS_D4 PE11 + #define LCD_PINS_ENABLE PE13 + #define LCD_PINS_D4 PE11 #else - #define LCD_PINS_RS PE8 + #define LCD_PINS_RS PE8 - #define BTN_EN1 PC5 - #define BTN_EN2 PB0 - #define SD_DETECT_PIN PC4 + #define BTN_EN1 PC5 + #define BTN_EN2 PB0 + #define SD_DETECT_PIN PC4 - #define LCD_SDSS PA4 + #define LCD_SDSS PA4 - #define LCD_PINS_ENABLE PE9 - #define LCD_PINS_D4 PE10 + #define LCD_PINS_ENABLE PE9 + #define LCD_PINS_D4 PE10 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PE11 - #define LCD_PINS_D6 PE12 - #define LCD_PINS_D7 PE13 + #define LCD_PINS_D5 PE11 + #define LCD_PINS_D6 PE12 + #define LCD_PINS_D7 PE13 #endif #endif @@ -240,14 +240,14 @@ // RGB LEDs // #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB5 + #define RGB_LED_R_PIN PB5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB4 + #define RGB_LED_G_PIN PB4 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB3 + #define RGB_LED_B_PIN PB3 #endif #ifndef RGB_LED_W_PIN - #define RGB_LED_W_PIN -1 + #define RGB_LED_W_PIN -1 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index eaef0b09df..ac8b731aae 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -33,121 +33,121 @@ // Use one of these or SDCard-based Emulation will be used //#define I2C_EEPROM -//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation +//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation -#define TP // Enable to define servo and probe pins +#define TP // Enable to define servo and probe pins // // Servos // #if ENABLED(TP) - #define SERVO0_PIN PB11 + #define SERVO0_PIN PB11 #endif -#define PS_ON_PIN PH6 +#define PS_ON_PIN PH6 // // Limit Switches // -#define X_MIN_PIN PF2 -#define X_MAX_PIN PG14 -#define Y_MIN_PIN PC13 -#define Y_MAX_PIN PG9 -#define Z_MIN_PIN PE0 -#define Z_MAX_PIN PD3 +#define X_MIN_PIN PF2 +#define X_MAX_PIN PG14 +#define Y_MIN_PIN PC13 +#define Y_MAX_PIN PG9 +#define Z_MIN_PIN PE0 +#define Z_MAX_PIN PD3 // // Pins on the extender // -//#define X_MIN_PIN PI4 -//#define X2_MIN_PIN PF12 -//#define Y_MIN_PIN PF4 -//#define Y2_MIN_PIN PI7 -//#define Z_MIN_PIN PF6 +//#define X_MIN_PIN PI4 +//#define X2_MIN_PIN PF12 +//#define Y_MIN_PIN PF4 +//#define Y2_MIN_PIN PI7 +//#define Z_MIN_PIN PF6 #if ENABLED(TP) && !defined(Z_MIN_PROBE_PIN) - #define Z_MIN_PROBE_PIN PH11 // Z Probe must be PH11 + #define Z_MIN_PROBE_PIN PH11 // Z Probe must be PH11 #endif // // Steppers // -#define X_STEP_PIN PC15 -#define X_DIR_PIN PF0 -#define X_ENABLE_PIN PF1 +#define X_STEP_PIN PC15 +#define X_DIR_PIN PF0 +#define X_ENABLE_PIN PF1 #ifndef X_CS_PIN - #define X_CS_PIN PC14 + #define X_CS_PIN PC14 #endif -#define Y_STEP_PIN PE3 -#define Y_DIR_PIN PE2 -#define Y_ENABLE_PIN PE4 +#define Y_STEP_PIN PE3 +#define Y_DIR_PIN PE2 +#define Y_ENABLE_PIN PE4 #ifndef Y_CS_PIN - #define Y_CS_PIN PE1 + #define Y_CS_PIN PE1 #endif -#define Z_STEP_PIN PB8 -#define Z_DIR_PIN PB7 // PB7 -#define Z_ENABLE_PIN PB9 +#define Z_STEP_PIN PB8 +#define Z_DIR_PIN PB7 // PB7 +#define Z_ENABLE_PIN PB9 #ifndef Z_CS_PIN - #define Z_CS_PIN PB5 + #define Z_CS_PIN PB5 #endif -#define E0_STEP_PIN PG12 -#define E0_DIR_PIN PG11 -#define E0_ENABLE_PIN PG13 +#define E0_STEP_PIN PG12 +#define E0_DIR_PIN PG11 +#define E0_ENABLE_PIN PG13 #ifndef E0_CS_PIN - #define E0_CS_PIN PG10 + #define E0_CS_PIN PG10 #endif -#define E1_STEP_PIN PD6 -#define E1_DIR_PIN PD5 -#define E1_ENABLE_PIN PD7 +#define E1_STEP_PIN PD6 +#define E1_DIR_PIN PD5 +#define E1_ENABLE_PIN PD7 #ifndef E1_CS_PIN - #define E1_CS_PIN PD4 + #define E1_CS_PIN PD4 #endif -#define E2_STEP_PIN PD1 -#define E2_DIR_PIN PD0 -#define E2_ENABLE_PIN PD2 +#define E2_STEP_PIN PD1 +#define E2_DIR_PIN PD0 +#define E2_ENABLE_PIN PD2 #ifndef E2_CS_PIN - #define E2_CS_PIN PC12 + #define E2_CS_PIN PC12 #endif -#define E3_STEP_PIN PF3 -#define E3_DIR_PIN PG3 -#define E3_ENABLE_PIN PF8 +#define E3_STEP_PIN PF3 +#define E3_DIR_PIN PG3 +#define E3_ENABLE_PIN PF8 #ifndef E3_CS_PIN - #define E3_CS_PIN PG4 + #define E3_CS_PIN PG4 #endif -#define E4_STEP_PIN PD14 -#define E4_DIR_PIN PD11 -#define E4_ENABLE_PIN PG2 +#define E4_STEP_PIN PD14 +#define E4_DIR_PIN PD11 +#define E4_ENABLE_PIN PG2 #ifndef E4_CS_PIN - #define E4_CS_PIN PE15 + #define E4_CS_PIN PE15 #endif -#define E5_STEP_PIN PE12 -#define E5_DIR_PIN PE10 -#define E5_ENABLE_PIN PF14 +#define E5_STEP_PIN PE12 +#define E5_DIR_PIN PE10 +#define E5_ENABLE_PIN PF14 #ifndef E5_CS_PIN - #define E5_CS_PIN PE7 + #define E5_CS_PIN PE7 #endif -#define E6_STEP_PIN PG0 -#define E6_DIR_PIN PG1 -#define E6_ENABLE_PIN PE8 +#define E6_STEP_PIN PG0 +#define E6_DIR_PIN PG1 +#define E6_ENABLE_PIN PE8 #ifndef E6_CS_PIN - #define E6_CS_PIN PF15 + #define E6_CS_PIN PF15 #endif -#define E7_STEP_PIN PH12 -#define E7_DIR_PIN PH15 -#define E7_ENABLE_PIN PI0 +#define E7_STEP_PIN PH12 +#define E7_DIR_PIN PH15 +#define E7_ENABLE_PIN PI0 #ifndef E7_CS_PIN - #define E7_CS_PIN PH14 + #define E7_CS_PIN PH14 #endif // @@ -155,13 +155,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PG15 + #define TMC_SW_MOSI PG15 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB6 + #define TMC_SW_MISO PB6 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 + #define TMC_SW_SCK PB3 #endif #endif @@ -190,38 +190,38 @@ // // Software serial // - #define X_SERIAL_TX_PIN PC14 - #define X_SERIAL_RX_PIN PC14 + #define X_SERIAL_TX_PIN PC14 + #define X_SERIAL_RX_PIN PC14 - #define Y_SERIAL_TX_PIN PE1 - #define Y_SERIAL_RX_PIN PE1 + #define Y_SERIAL_TX_PIN PE1 + #define Y_SERIAL_RX_PIN PE1 - #define Z_SERIAL_TX_PIN PB5 - #define Z_SERIAL_RX_PIN PB5 + #define Z_SERIAL_TX_PIN PB5 + #define Z_SERIAL_RX_PIN PB5 - #define E0_SERIAL_TX_PIN PG10 - #define E0_SERIAL_RX_PIN PG10 + #define E0_SERIAL_TX_PIN PG10 + #define E0_SERIAL_RX_PIN PG10 - #define E1_SERIAL_TX_PIN PD4 - #define E1_SERIAL_RX_PIN PD4 + #define E1_SERIAL_TX_PIN PD4 + #define E1_SERIAL_RX_PIN PD4 - #define E2_SERIAL_TX_PIN PC12 - #define E2_SERIAL_RX_PIN PC12 + #define E2_SERIAL_TX_PIN PC12 + #define E2_SERIAL_RX_PIN PC12 - #define E3_SERIAL_TX_PIN PG4 - #define E3_SERIAL_RX_PIN PG4 + #define E3_SERIAL_TX_PIN PG4 + #define E3_SERIAL_RX_PIN PG4 - #define E4_SERIAL_TX_PIN PE15 - #define E4_SERIAL_RX_PIN PE15 + #define E4_SERIAL_TX_PIN PE15 + #define E4_SERIAL_RX_PIN PE15 - #define E5_SERIAL_TX_PIN PE7 - #define E5_SERIAL_RX_PIN PE7 + #define E5_SERIAL_TX_PIN PE7 + #define E5_SERIAL_RX_PIN PE7 - #define E6_SERIAL_TX_PIN PF15 - #define E6_SERIAL_RX_PIN PF15 + #define E6_SERIAL_TX_PIN PF15 + #define E6_SERIAL_RX_PIN PF15 - #define E7_SERIAL_TX_PIN PH14 - #define E7_SERIAL_RX_PIN PH14 + #define E7_SERIAL_TX_PIN PH14 + #define E7_SERIAL_RX_PIN PH14 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -230,75 +230,75 @@ // // Temperature Sensors // -#define TEMP_0_PIN PC1 // T1 <-> E0 -#define TEMP_1_PIN PC2 // T2 <-> E1 -#define TEMP_2_PIN PC3 // T3 <-> E2 +#define TEMP_0_PIN PC1 // T1 <-> E0 +#define TEMP_1_PIN PC2 // T2 <-> E1 +#define TEMP_2_PIN PC3 // T3 <-> E2 -#define TEMP_3_PIN PA3 // T4 <-> E3 -#define TEMP_4_PIN PF9 // T5 <-> E4 -#define TEMP_5_PIN PF10 // T6 <-> E5 -#define TEMP_6_PIN PF7 // T7 <-> E6 -#define TEMP_7_PIN PF5 // T8 <-> E7 +#define TEMP_3_PIN PA3 // T4 <-> E3 +#define TEMP_4_PIN PF9 // T5 <-> E4 +#define TEMP_5_PIN PF10 // T6 <-> E5 +#define TEMP_6_PIN PF7 // T7 <-> E6 +#define TEMP_7_PIN PF5 // T8 <-> E7 -#define TEMP_BED_PIN PC0 // T0 <-> Bed +#define TEMP_BED_PIN PC0 // T0 <-> Bed // SPI for Max6675 or Max31855 Thermocouple // Uses a separate SPI bus // If you have a two-way thermocouple, you can customize two THERMO_CSx_PIN pins (x:1~2) -#define THERMO_SCK_PIN PI1 // SCK -#define THERMO_DO_PIN PI2 // MISO -#define THERMO_CS1_PIN PH9 // CS1 -#define THERMO_CS2_PIN PH2 // CS2 +#define THERMO_SCK_PIN PI1 // SCK +#define THERMO_DO_PIN PI2 // MISO +#define THERMO_CS1_PIN PH9 // CS1 +#define THERMO_CS2_PIN PH2 // CS2 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#define MAX6675_SS_PIN THERMO_CS1_PIN +#define MAX6675_SS2_PIN THERMO_CS2_PIN +#define MAX6675_SCK_PIN THERMO_SCK_PIN +#define MAX6675_DO_PIN THERMO_DO_PIN // // Heaters / Fans // -#define HEATER_0_PIN PB1 // Heater0 -#define HEATER_1_PIN PA1 // Heater1 -#define HEATER_2_PIN PB0 // Heater2 +#define HEATER_0_PIN PB1 // Heater0 +#define HEATER_1_PIN PA1 // Heater1 +#define HEATER_2_PIN PB0 // Heater2 -#define HEATER_3_PIN PD15 // Heater3 -#define HEATER_4_PIN PD13 // Heater4 -#define HEATER_5_PIN PD12 // Heater5 -#define HEATER_6_PIN PE13 // Heater6 -#define HEATER_7_PIN PI6 // Heater7 +#define HEATER_3_PIN PD15 // Heater3 +#define HEATER_4_PIN PD13 // Heater4 +#define HEATER_5_PIN PD12 // Heater5 +#define HEATER_6_PIN PE13 // Heater6 +#define HEATER_7_PIN PI6 // Heater7 -#define HEATER_BED_PIN PA2 // Hotbed +#define HEATER_BED_PIN PA2 // Hotbed -#define FAN_PIN PE5 // Fan0 -#define FAN1_PIN PE6 // Fan1 -#define FAN2_PIN PC8 // Fan2 +#define FAN_PIN PE5 // Fan0 +#define FAN1_PIN PE6 // Fan1 +#define FAN2_PIN PC8 // Fan2 -#define FAN3_PIN PI5 // Fan3 -#define FAN4_PIN PE9 // Fan4 -#define FAN5_PIN PE11 // Fan5 -//#define FAN6_PIN PC9 // Fan6 -//#define FAN7_PIN PE14 // Fan7 +#define FAN3_PIN PI5 // Fan3 +#define FAN4_PIN PE9 // Fan4 +#define FAN5_PIN PE11 // Fan5 +//#define FAN6_PIN PC9 // Fan6 +//#define FAN7_PIN PE14 // Fan7 // // By default the onboard SD (SPI1) is enabled // #define CUSTOM_SPI_PINS #if DISABLED(CUSTOM_SPI_PINS) - #define SDSS PB12 + #define SDSS PB12 #endif // HAL SPI1 pins group #if ENABLED(CUSTOM_SPI_PINS) - #define SDSS PA4 - #define SD_DETECT_PIN PC4 - #define LCD_SDSS PA4 + #define SDSS PA4 + #define SD_DETECT_PIN PC4 + #define LCD_SDSS PA4 - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PA7 - #define SS_PIN PA4 // Chip select for SD card used by Marlin + #define SCK_PIN PA5 + #define MISO_PIN PA6 + #define MOSI_PIN PA7 + #define SS_PIN PA4 // Chip select for SD card used by Marlin #endif /** @@ -316,18 +316,18 @@ // LCDs and Controllers // #if HAS_SPI_LCD - #define BEEPER_PIN PC11 - #define BTN_ENC PA15 + #define BEEPER_PIN PC11 + #define BTN_ENC PA15 #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PA8 + #define LCD_PINS_RS PA8 - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define BTN_EN1 PD10 + #define BTN_EN2 PH10 - #define LCD_PINS_ENABLE PG7 - #define LCD_PINS_D4 PG8 + #define LCD_PINS_ENABLE PG7 + #define LCD_PINS_D4 PG8 //#undef ST7920_DELAY_1 //#undef ST7920_DELAY_2 @@ -335,43 +335,43 @@ #else - #define LCD_PINS_RS PA8 + #define LCD_PINS_RS PA8 - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define BTN_EN1 PD10 + #define BTN_EN2 PH10 #if DISABLED(CUSTOM_SPI_PINS) - #define SD_DETECT_PIN PB10 - #define LCD_SDSS PB12 + #define SD_DETECT_PIN PB10 + #define LCD_SDSS PB12 #endif - #define LCD_PINS_ENABLE PC10 - #define LCD_PINS_D4 PG8 + #define LCD_PINS_ENABLE PC10 + #define LCD_PINS_D4 PG8 #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS PC10 - #define DOGLCD_A0 PA8 - //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PG8 // Must be high or open for LCD to operate normally. + #define DOGLCD_CS PC10 + #define DOGLCD_A0 PA8 + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PG8 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PG7 + #define RGB_LED_R_PIN PG7 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PG6 + #define RGB_LED_G_PIN PG6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PG5 + #define RGB_LED_B_PIN PG5 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PF13 + #define NEOPIXEL_PIN PF13 #endif #endif // !FYSETC_MINI_12864 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PG7 - #define LCD_PINS_D6 PG6 - #define LCD_PINS_D7 PG5 + #define LCD_PINS_D5 PG7 + #define LCD_PINS_D6 PG6 + #define LCD_PINS_D7 PG5 #endif #endif @@ -383,9 +383,9 @@ #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif - //#define DOGLCD_CS PB12 - //#define DOGLCD_A0 PA8 - //#define LCD_PINS_DC PB14 - //#define DOGLCD_MOSI PB15 + //#define DOGLCD_CS PB12 + //#define DOGLCD_A0 PA8 + //#define LCD_PINS_DC PB14 + //#define DOGLCD_MOSI PB15 #endif // HAS_SPI_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 3376a99711..4dbdf0e77f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -30,74 +30,74 @@ #define BOARD_INFO_NAME "BIGTREE SKR Pro 1.1" // redefined? // Use one of these or SDCard-based Emulation will be used -//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation +//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation // // Servos // -#define SERVO0_PIN PA1 +#define SERVO0_PIN PA1 // // Limit Switches // -#define X_MIN_PIN PB10 -#define X_MAX_PIN PE15 -#define Y_MIN_PIN PE12 -#define Y_MAX_PIN PE10 -#define Z_MIN_PIN PG8 -#define Z_MAX_PIN PG5 +#define X_MIN_PIN PB10 +#define X_MAX_PIN PE15 +#define Y_MIN_PIN PE12 +#define Y_MAX_PIN PE10 +#define Z_MIN_PIN PG8 +#define Z_MAX_PIN PG5 // // Z Probe must be this pins // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PA2 + #define Z_MIN_PROBE_PIN PA2 #endif // // Steppers // -#define X_STEP_PIN PE9 -#define X_DIR_PIN PF1 -#define X_ENABLE_PIN PF2 +#define X_STEP_PIN PE9 +#define X_DIR_PIN PF1 +#define X_ENABLE_PIN PF2 #ifndef X_CS_PIN - #define X_CS_PIN PA15 + #define X_CS_PIN PA15 #endif -#define Y_STEP_PIN PE11 -#define Y_DIR_PIN PE8 -#define Y_ENABLE_PIN PD7 +#define Y_STEP_PIN PE11 +#define Y_DIR_PIN PE8 +#define Y_ENABLE_PIN PD7 #ifndef Y_CS_PIN - #define Y_CS_PIN PB8 + #define Y_CS_PIN PB8 #endif -#define Z_STEP_PIN PE13 -#define Z_DIR_PIN PC2 -#define Z_ENABLE_PIN PC0 +#define Z_STEP_PIN PE13 +#define Z_DIR_PIN PC2 +#define Z_ENABLE_PIN PC0 #ifndef Z_CS_PIN - #define Z_CS_PIN PB9 + #define Z_CS_PIN PB9 #endif -#define E0_STEP_PIN PE14 -#define E0_DIR_PIN PA0 -#define E0_ENABLE_PIN PC3 +#define E0_STEP_PIN PE14 +#define E0_DIR_PIN PA0 +#define E0_ENABLE_PIN PC3 #ifndef E0_CS_PIN - #define E0_CS_PIN PB3 + #define E0_CS_PIN PB3 #endif -#define E1_STEP_PIN PD15 -#define E1_DIR_PIN PE7 -#define E1_ENABLE_PIN PA3 +#define E1_STEP_PIN PD15 +#define E1_DIR_PIN PE7 +#define E1_ENABLE_PIN PA3 #ifndef E1_CS_PIN - #define E1_CS_PIN PG15 + #define E1_CS_PIN PG15 #endif -#define E2_STEP_PIN PD13 -#define E2_DIR_PIN PG9 -#define E2_ENABLE_PIN PF0 +#define E2_STEP_PIN PD13 +#define E2_DIR_PIN PG9 +#define E2_ENABLE_PIN PF0 #ifndef E2_CS_PIN - #define E2_CS_PIN PG12 + #define E2_CS_PIN PG12 #endif // @@ -105,13 +105,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PC12 + #define TMC_SW_MOSI PC12 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PC11 + #define TMC_SW_MISO PC11 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PC10 + #define TMC_SW_SCK PC10 #endif #endif @@ -137,23 +137,23 @@ // // Software serial // - #define X_SERIAL_TX_PIN PC13 - #define X_SERIAL_RX_PIN PC13 + #define X_SERIAL_TX_PIN PC13 + #define X_SERIAL_RX_PIN PC13 - #define Y_SERIAL_TX_PIN PE3 - #define Y_SERIAL_RX_PIN PE3 + #define Y_SERIAL_TX_PIN PE3 + #define Y_SERIAL_RX_PIN PE3 - #define Z_SERIAL_TX_PIN PE1 - #define Z_SERIAL_RX_PIN PE1 + #define Z_SERIAL_TX_PIN PE1 + #define Z_SERIAL_RX_PIN PE1 - #define E0_SERIAL_TX_PIN PD4 - #define E0_SERIAL_RX_PIN PD4 + #define E0_SERIAL_TX_PIN PD4 + #define E0_SERIAL_RX_PIN PD4 - #define E1_SERIAL_TX_PIN PD1 - #define E1_SERIAL_RX_PIN PD1 + #define E1_SERIAL_TX_PIN PD1 + #define E1_SERIAL_RX_PIN PD1 - #define E2_SERIAL_TX_PIN PD6 - #define E2_SERIAL_RX_PIN PD6 + #define E2_SERIAL_TX_PIN PD6 + #define E2_SERIAL_RX_PIN PD6 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -162,28 +162,28 @@ // // Temperature Sensors // -#define TEMP_0_PIN PF4 // T1 <-> E0 -#define TEMP_1_PIN PF5 // T2 <-> E1 -#define TEMP_2_PIN PF6 // T3 <-> E2 -#define TEMP_BED_PIN PF3 // T0 <-> Bed +#define TEMP_0_PIN PF4 // T1 <-> E0 +#define TEMP_1_PIN PF5 // T2 <-> E1 +#define TEMP_2_PIN PF6 // T3 <-> E2 +#define TEMP_BED_PIN PF3 // T0 <-> Bed // // Heaters / Fans // -#define HEATER_0_PIN PB1 // Heater0 -#define HEATER_1_PIN PD14 // Heater1 -#define HEATER_2_PIN PB0 // Heater1 -#define HEATER_BED_PIN PD12 // Hotbed -#define FAN_PIN PC8 // Fan0 -#define FAN1_PIN PE5 // Fan1 -#define FAN2_PIN PE6 // Fan2 +#define HEATER_0_PIN PB1 // Heater0 +#define HEATER_1_PIN PD14 // Heater1 +#define HEATER_2_PIN PB0 // Heater1 +#define HEATER_BED_PIN PD12 // Hotbed +#define FAN_PIN PC8 // Fan0 +#define FAN1_PIN PE5 // Fan1 +#define FAN2_PIN PE6 // Fan2 // // Misc. Functions // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #endif // @@ -191,16 +191,15 @@ // NOT compatible with LCD // #if SDCARD_CONNECTION == ONBOARD && !HAS_SPI_LCD - #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS PA4 - #define SCK_PIN PA5 - #define MISO_PIN PA6 - #define MOSI_PIN PB5 + #define SOFTWARE_SPI // Use soft SPI for onboard SD + #define SDSS PA4 + #define SCK_PIN PA5 + #define MISO_PIN PA6 + #define MOSI_PIN PB5 #else - #define SDSS PB12 + #define SDSS PB12 #endif - /** * _____ _____ * NC | · · | GND 5V | · · | GND @@ -216,17 +215,17 @@ // LCDs and Controllers // #if HAS_SPI_LCD - #define BEEPER_PIN PG4 - #define BTN_ENC PA8 + #define BEEPER_PIN PG4 + #define BTN_ENC PA8 #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PG6 + #define LCD_PINS_RS PG6 - #define BTN_EN1 PD11 - #define BTN_EN2 PG2 + #define BTN_EN1 PD11 + #define BTN_EN2 PG2 - #define LCD_PINS_ENABLE PG7 - #define LCD_PINS_D4 PG3 + #define LCD_PINS_ENABLE PG7 + #define LCD_PINS_D4 PG3 // CR10_Stock Display needs a different delay setting on SKR PRO v1.1, so undef it here. // It will be defined again at the #HAS_GRAPHICAL_LCD section below. @@ -234,44 +233,43 @@ #undef ST7920_DELAY_2 #undef ST7920_DELAY_3 - #else - #define LCD_PINS_RS PD10 + #define LCD_PINS_RS PD10 - #define BTN_EN1 PG10 - #define BTN_EN2 PF11 - #define SD_DETECT_PIN PF12 + #define BTN_EN1 PG10 + #define BTN_EN2 PF11 + #define SD_DETECT_PIN PF12 - #define LCD_SDSS PB12 + #define LCD_SDSS PB12 - #define LCD_PINS_ENABLE PD11 - #define LCD_PINS_D4 PG2 + #define LCD_PINS_ENABLE PD11 + #define LCD_PINS_D4 PG2 #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS PD11 - #define DOGLCD_A0 PD10 - //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PG2 // Must be high or open for LCD to operate normally. + #define DOGLCD_CS PD11 + #define DOGLCD_A0 PD10 + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PG2 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PG3 + #define RGB_LED_R_PIN PG3 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PG6 + #define RGB_LED_G_PIN PG6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PG7 + #define RGB_LED_B_PIN PG7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PG3 + #define NEOPIXEL_PIN PG3 #endif #endif // !FYSETC_MINI_12864 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PG3 - #define LCD_PINS_D6 PG6 - #define LCD_PINS_D7 PG7 + #define LCD_PINS_D5 PG3 + #define LCD_PINS_D6 PG6 + #define LCD_PINS_D7 PG7 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 8c8ea2adc1..8205cd9f4d 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -32,147 +32,147 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #undef E2END -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB // // Servos // -#define SERVO0_PIN PE11 +#define SERVO0_PIN PE11 // // Limit Switches // -#define X_MIN_PIN PC3 -#define X_MAX_PIN PC2 -#define Y_MIN_PIN PF2 -#define Y_MAX_PIN PF1 -#define Z_MIN_PIN PF0 -#define Z_MAX_PIN PC15 +#define X_MIN_PIN PC3 +#define X_MAX_PIN PC2 +#define Y_MIN_PIN PF2 +#define Y_MAX_PIN PF1 +#define Z_MIN_PIN PF0 +#define Z_MAX_PIN PC15 // // Z Probe (when not Z_MIN_PIN) // -#define Z_MIN_PROBE_PIN PC14 // Z3_PIN +#define Z_MIN_PROBE_PIN PC14 // Z3_PIN // // Steppers // -#define X_STEP_PIN PB9 -#define X_DIR_PIN PE0 -#define X_ENABLE_PIN PE1 +#define X_STEP_PIN PB9 +#define X_DIR_PIN PE0 +#define X_ENABLE_PIN PE1 #ifndef X_CS_PIN - #define X_CS_PIN PG13 + #define X_CS_PIN PG13 #endif -#define Y_STEP_PIN PB8 -#define Y_DIR_PIN PG11 -#define Y_ENABLE_PIN PG12 +#define Y_STEP_PIN PB8 +#define Y_DIR_PIN PG11 +#define Y_ENABLE_PIN PG12 #ifndef Y_CS_PIN - #define Y_CS_PIN PG10 + #define Y_CS_PIN PG10 #endif -#define Z_STEP_PIN PA8 -#define Z_DIR_PIN PD6 -#define Z_ENABLE_PIN PD7 +#define Z_STEP_PIN PA8 +#define Z_DIR_PIN PD6 +#define Z_ENABLE_PIN PD7 #ifndef Z_CS_PIN - #define Z_CS_PIN PD5 + #define Z_CS_PIN PD5 #endif -#define E0_STEP_PIN PC7 -#define E0_DIR_PIN PD3 -#define E0_ENABLE_PIN PD4 +#define E0_STEP_PIN PC7 +#define E0_DIR_PIN PD3 +#define E0_ENABLE_PIN PD4 #ifndef E0_CS_PIN - #define E0_CS_PIN PD1 + #define E0_CS_PIN PD1 #endif -#define E1_STEP_PIN PC6 -#define E1_DIR_PIN PA15 -#define E1_ENABLE_PIN PD0 +#define E1_STEP_PIN PC6 +#define E1_DIR_PIN PA15 +#define E1_ENABLE_PIN PD0 #ifndef E1_CS_PIN - #define E1_CS_PIN PA14 + #define E1_CS_PIN PA14 #endif -#define E2_STEP_PIN PD15 -#define E2_DIR_PIN PG7 -#define E2_ENABLE_PIN PG8 +#define E2_STEP_PIN PD15 +#define E2_DIR_PIN PG7 +#define E2_ENABLE_PIN PG8 #ifndef E2_CS_PIN - #define E2_CS_PIN PG6 + #define E2_CS_PIN PG6 #endif -#define E3_STEP_PIN PD14 -#define E3_DIR_PIN PG4 -#define E3_ENABLE_PIN PG5 +#define E3_STEP_PIN PD14 +#define E3_DIR_PIN PG4 +#define E3_ENABLE_PIN PG5 #ifndef E3_CS_PIN - #define E3_CS_PIN PG3 + #define E3_CS_PIN PG3 #endif -#define E4_STEP_PIN PD13 -#define E4_DIR_PIN PD11 -#define E4_ENABLE_PIN PG2 +#define E4_STEP_PIN PD13 +#define E4_DIR_PIN PD11 +#define E4_ENABLE_PIN PG2 #ifndef E4_CS_PIN - #define E4_CS_PIN PD10 + #define E4_CS_PIN PD10 #endif -#define E5_STEP_PIN PD12 -#define E5_DIR_PIN PD8 -#define E5_ENABLE_PIN PD9 +#define E5_STEP_PIN PD12 +#define E5_DIR_PIN PD8 +#define E5_ENABLE_PIN PD9 #ifndef E5_CS_PIN - #define E5_CS_PIN PB12 + #define E5_CS_PIN PB12 #endif // // Temperature Sensors // -#define TEMP_0_PIN PA0 // Analog Input -#define TEMP_1_PIN PC1 // Analog Input -#define TEMP_2_PIN PC0 // Analog Input -#define TEMP_3_PIN PF10 // Analog Input -#define TEMP_4_PIN PF5 // Analog Input -#define TEMP_5_PIN PF4 // Analog Input -#define TEMP_BED_PIN PF3 // Analog Input +#define TEMP_0_PIN PA0 // Analog Input +#define TEMP_1_PIN PC1 // Analog Input +#define TEMP_2_PIN PC0 // Analog Input +#define TEMP_3_PIN PF10 // Analog Input +#define TEMP_4_PIN PF5 // Analog Input +#define TEMP_5_PIN PF4 // Analog Input +#define TEMP_BED_PIN PF3 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PF7 -#define HEATER_1_PIN PF6 -#define HEATER_2_PIN PE6 -#define HEATER_3_PIN PE5 -#define HEATER_4_PIN PE4 -#define HEATER_5_PIN PA2 -#define HEATER_BED_PIN PE2 +#define HEATER_0_PIN PF7 +#define HEATER_1_PIN PF6 +#define HEATER_2_PIN PE6 +#define HEATER_3_PIN PE5 +#define HEATER_4_PIN PE4 +#define HEATER_5_PIN PA2 +#define HEATER_BED_PIN PE2 #ifndef FAN_PIN - #define FAN_PIN PF8 + #define FAN_PIN PF8 #endif -#define FAN1_PIN PF9 -#define FAN2_PIN PE3 -#define FAN3_PIN PA1 -#define FAN4_PIN PE13 -#define FAN5_PIN PB11 +#define FAN1_PIN PF9 +#define FAN2_PIN PE3 +#define FAN3_PIN PA1 +#define FAN4_PIN PE13 +#define FAN5_PIN PB11 // // Onboard SD support // -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -//#define SD_CARD_DETECT_PIN PC13 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +//#define SD_CARD_DETECT_PIN PC13 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 #if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT - #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SCK_PIN SDIO_CK_PIN - #define MISO_PIN SDIO_D0_PIN - #define MOSI_PIN SDIO_CMD_PIN + #define SOFTWARE_SPI // Use soft SPI for onboard SD + #define SDSS SDIO_D3_PIN + #define SCK_PIN SDIO_CK_PIN + #define MISO_PIN SDIO_D0_PIN + #define MOSI_PIN SDIO_CMD_PIN #endif #endif @@ -182,13 +182,13 @@ #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 + #define TMC_SW_MOSI PB15 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 + #define TMC_SW_MISO PB14 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 + #define TMC_SW_SCK PB13 #endif #endif @@ -197,70 +197,69 @@ // #if HAS_TMC_UART - #define X_SERIAL_TX_PIN PG13 - #define X_SERIAL_RX_PIN PG13 + #define X_SERIAL_TX_PIN PG13 + #define X_SERIAL_RX_PIN PG13 - #define Y_SERIAL_TX_PIN PG10 - #define Y_SERIAL_RX_PIN PG10 + #define Y_SERIAL_TX_PIN PG10 + #define Y_SERIAL_RX_PIN PG10 - #define Z_SERIAL_TX_PIN PD5 - #define Z_SERIAL_RX_PIN PD5 + #define Z_SERIAL_TX_PIN PD5 + #define Z_SERIAL_RX_PIN PD5 - #define E0_SERIAL_TX_PIN PD1 - #define E0_SERIAL_RX_PIN PD1 + #define E0_SERIAL_TX_PIN PD1 + #define E0_SERIAL_RX_PIN PD1 - #define E1_SERIAL_TX_PIN PA14 - #define E1_SERIAL_RX_PIN PA14 + #define E1_SERIAL_TX_PIN PA14 + #define E1_SERIAL_RX_PIN PA14 - #define E2_SERIAL_TX_PIN PG6 - #define E2_SERIAL_RX_PIN PG6 + #define E2_SERIAL_TX_PIN PG6 + #define E2_SERIAL_RX_PIN PG6 - #define E3_SERIAL_TX_PIN PG3 - #define E3_SERIAL_RX_PIN PG3 + #define E3_SERIAL_TX_PIN PG3 + #define E3_SERIAL_RX_PIN PG3 - #define E4_SERIAL_TX_PIN PD10 - #define E4_SERIAL_RX_PIN PD10 + #define E4_SERIAL_TX_PIN PD10 + #define E4_SERIAL_RX_PIN PD10 - #define E5_SERIAL_TX_PIN PB12 - #define E5_SERIAL_RX_PIN PB12 + #define E5_SERIAL_TX_PIN PB12 + #define E5_SERIAL_RX_PIN PB12 #endif - // // LCD / Controller // -#define SCK_PIN PB13 -#define MISO_PIN PB14 -#define MOSI_PIN PB15 -#define SDSS PF11 -#define SD_DETECT_PIN PB2 -#define BEEPER_PIN PB10 -#define LCD_PINS_RS PE12 -#define LCD_PINS_ENABLE PE14 -#define LCD_PINS_D4 PE10 -#define LCD_PINS_D5 PE9 -#define LCD_PINS_D6 PE8 -#define LCD_PINS_D7 PE7 -#define BTN_EN1 PC4 -#define BTN_EN2 PC5 -#define BTN_ENC PE15 +#define SCK_PIN PB13 +#define MISO_PIN PB14 +#define MOSI_PIN PB15 +#define SDSS PF11 +#define SD_DETECT_PIN PB2 +#define BEEPER_PIN PB10 +#define LCD_PINS_RS PE12 +#define LCD_PINS_ENABLE PE14 +#define LCD_PINS_D4 PE10 +#define LCD_PINS_D5 PE9 +#define LCD_PINS_D6 PE8 +#define LCD_PINS_D7 PE7 +#define BTN_EN1 PC4 +#define BTN_EN2 PC5 +#define BTN_ENC PE15 // // Filament runout // -#define FIL_RUNOUT_PIN PA3 +#define FIL_RUNOUT_PIN PA3 // // ST7920 Delays // #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(96) + #define ST7920_DELAY_1 DELAY_NS(96) #endif #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(48) + #define ST7920_DELAY_2 DELAY_NS(48) #endif #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(715) + #define ST7920_DELAY_3 DELAY_NS(715) #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index d135ef0750..bdadbe36c2 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -47,65 +47,65 @@ //#define SRAM_EEPROM_EMULATION //#define I2C_EEPROM #ifdef I2C_EEPROM - #undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. - #define E2END 0xFFF // 4KB + #undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. + #define E2END 0xFFF // 4KB #endif // // Servos // -#define SERVO0_PIN PA3 +#define SERVO0_PIN PA3 // // Limit Switches // -#define X_MIN_PIN PB14 -#define X_MAX_PIN PA1 -#define Y_MIN_PIN PB13 -#define Y_MAX_PIN PA2 -#define Z_MIN_PIN PA0 -#define Z_MAX_PIN PA3 +#define X_MIN_PIN PB14 +#define X_MAX_PIN PA1 +#define Y_MIN_PIN PB13 +#define Y_MAX_PIN PA2 +#define Z_MIN_PIN PA0 +#define Z_MAX_PIN PA3 // // Filament Sensor // share with X_MAX_PIN // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA1 + #define FIL_RUNOUT_PIN PA1 #endif // // Steppers // -#define X_STEP_PIN PE11 -#define X_DIR_PIN PE10 -#define X_ENABLE_PIN PE12 -#define X_CS_PIN PE7 +#define X_STEP_PIN PE11 +#define X_DIR_PIN PE10 +#define X_ENABLE_PIN PE12 +#define X_CS_PIN PE7 -#define Y_STEP_PIN PD8 -#define Y_DIR_PIN PB12 -#define Y_ENABLE_PIN PD9 -#define Y_CS_PIN PE15 +#define Y_STEP_PIN PD8 +#define Y_DIR_PIN PB12 +#define Y_ENABLE_PIN PD9 +#define Y_CS_PIN PE15 -#define Z_STEP_PIN PD14 -#define Z_DIR_PIN PD13 -#define Z_ENABLE_PIN PD15 -#define Z_CS_PIN PD10 +#define Z_STEP_PIN PD14 +#define Z_DIR_PIN PD13 +#define Z_ENABLE_PIN PD15 +#define Z_CS_PIN PD10 -#define E0_STEP_PIN PD5 -#define E0_DIR_PIN PD6 -#define E0_ENABLE_PIN PD4 -#define E0_CS_PIN PD7 +#define E0_STEP_PIN PD5 +#define E0_DIR_PIN PD6 +#define E0_ENABLE_PIN PD4 +#define E0_CS_PIN PD7 -#define E1_STEP_PIN PE6 -#define E1_DIR_PIN PC13 -#define E1_ENABLE_PIN PE5 -#define E1_CS_PIN PC14 +#define E1_STEP_PIN PE6 +#define E1_DIR_PIN PC13 +#define E1_ENABLE_PIN PE5 +#define E1_CS_PIN PC14 -#define E2_STEP_PIN PE2 -#define E2_DIR_PIN PE4 -#define E2_ENABLE_PIN PE3 -#define E2_CS_PIN PC15 +#define E2_STEP_PIN PE2 +#define E2_DIR_PIN PE4 +#define E2_ENABLE_PIN PE3 +#define E2_CS_PIN PC15 #if HAS_TMC_UART // @@ -115,78 +115,78 @@ // // Software serial // - #define X_SERIAL_TX_PIN PE9 - #define X_SERIAL_RX_PIN PE8 + #define X_SERIAL_TX_PIN PE9 + #define X_SERIAL_RX_PIN PE8 - #define Y_SERIAL_TX_PIN PE14 - #define Y_SERIAL_RX_PIN PE13 + #define Y_SERIAL_TX_PIN PE14 + #define Y_SERIAL_RX_PIN PE13 - #define Z_SERIAL_TX_PIN PD11 - #define Z_SERIAL_RX_PIN PD12 + #define Z_SERIAL_TX_PIN PD11 + #define Z_SERIAL_RX_PIN PD12 - #define E0_SERIAL_TX_PIN PD3 - #define E0_SERIAL_RX_PIN PA15 + #define E0_SERIAL_TX_PIN PD3 + #define E0_SERIAL_RX_PIN PA15 - #define E1_SERIAL_TX_PIN PC4 - #define E1_SERIAL_RX_PIN PC5 + #define E1_SERIAL_TX_PIN PC4 + #define E1_SERIAL_RX_PIN PC5 - #define E2_SERIAL_TX_PIN PE1 - #define E2_SERIAL_RX_PIN PE0 + #define E2_SERIAL_TX_PIN PE1 + #define E2_SERIAL_RX_PIN PE0 #endif // // Temperature Sensors // -#define TEMP_0_PIN PC0 -#define TEMP_1_PIN PC1 -#define TEMP_2_PIN PC2 -#define TEMP_BED_PIN PC3 +#define TEMP_0_PIN PC0 +#define TEMP_1_PIN PC1 +#define TEMP_2_PIN PC2 +#define TEMP_BED_PIN PC3 // // Heaters / Fans // -#define HEATER_0_PIN PB3 -#define HEATER_1_PIN PB4 -#define HEATER_2_PIN PB15 -#define HEATER_BED_PIN PC8 +#define HEATER_0_PIN PB3 +#define HEATER_1_PIN PB4 +#define HEATER_2_PIN PB15 +#define HEATER_BED_PIN PC8 -#define FAN_PIN PB0 -#define FAN1_PIN PB1 -#define FAN2_PIN PB2 +#define FAN_PIN PB0 +#define FAN1_PIN PB1 +#define FAN2_PIN PB2 // // SPI // -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 +#define SCK_PIN PA5 +#define MISO_PIN PA6 +#define MOSI_PIN PA7 // // Misc. Functions // -//#define LED_PIN PB14 -//#define BTN_PIN PC10 -//#define PS_ON_PIN PE11 -//#define KILL_PIN PC5 +//#define LED_PIN PB14 +//#define BTN_PIN PC10 +//#define PS_ON_PIN PE11 +//#define KILL_PIN PC5 -#define SDSS PA4 -#define SD_DETECT_PIN PB10 +#define SDSS PA4 +#define SD_DETECT_PIN PB10 // // LCD / Controller // #if HAS_SPI_LCD - #define BEEPER_PIN PC9 - #define BTN_ENC PA8 + #define BEEPER_PIN PC9 + #define BTN_ENC PA8 #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PD0 + #define LCD_PINS_RS PD0 - #define BTN_EN1 PC11 - #define BTN_EN2 PC10 + #define BTN_EN1 PC11 + #define BTN_EN2 PC10 - #define LCD_PINS_ENABLE PD1 - #define LCD_PINS_D4 PC12 + #define LCD_PINS_ENABLE PD1 + #define LCD_PINS_D4 PC12 // CR10_Stock Display needs a different delay setting on SKR PRO v1.1, so undef it here. // It will be defined again at the #HAS_GRAPHICAL_LCD section below. @@ -196,43 +196,43 @@ #else - #define LCD_PINS_RS PD2 + #define LCD_PINS_RS PD2 - #define BTN_EN1 PC6 - #define BTN_EN2 PC7 + #define BTN_EN1 PC6 + #define BTN_EN2 PC7 - #define LCD_SDSS PA4 + #define LCD_SDSS PA4 - #define LCD_PINS_ENABLE PC11 - #define LCD_PINS_D4 PC10 + #define LCD_PINS_ENABLE PC11 + #define LCD_PINS_D4 PC10 #if ENABLED(FYSETC_MINI_12864) // See https://wiki.fysetc.com/Mini12864_Panel - #define DOGLCD_CS PC11 - #define DOGLCD_A0 PD2 + #define DOGLCD_CS PC11 + #define DOGLCD_A0 PD2 #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN PD0 + #define LCD_BACKLIGHT_PIN PD0 #endif - #define LCD_RESET_PIN PC10 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN PC10 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PC12 + #define RGB_LED_R_PIN PC12 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PD0 + #define RGB_LED_G_PIN PD0 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PD1 + #define RGB_LED_B_PIN PD1 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PC12 + #define NEOPIXEL_PIN PC12 #endif #endif // !FYSETC_MINI_12864 #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PC12 - #define LCD_PINS_D6 PD0 - #define LCD_PINS_D7 PD1 + #define LCD_PINS_D5 PC12 + #define LCD_PINS_D6 PD0 + #define LCD_PINS_D7 PD1 #endif #endif @@ -240,27 +240,27 @@ // Alter timing for graphical display #if HAS_GRAPHICAL_LCD #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(96) + #define ST7920_DELAY_1 DELAY_NS(96) #endif #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(48) + #define ST7920_DELAY_2 DELAY_NS(48) #endif #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(600) + #define ST7920_DELAY_3 DELAY_NS(600) #endif #endif #endif // HAS_SPI_LCD #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB6 + #define RGB_LED_R_PIN PB6 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB5 + #define RGB_LED_G_PIN PB5 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB7 + #define RGB_LED_B_PIN PB7 #endif #ifndef RGB_LED_W_PIN - #define RGB_LED_W_PIN -1 + #define RGB_LED_W_PIN -1 #endif diff --git a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h index 2909b7c538..924b94c4f1 100644 --- a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h +++ b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h @@ -37,7 +37,7 @@ //#define I2C_EEPROM #ifndef E2END - #define E2END 0xFFF // 4KB + #define E2END 0xFFF // 4KB #endif // Ignore temp readings during development. @@ -46,12 +46,12 @@ // // Limit Switches // -#define X_MIN_PIN PE0 -#define X_MAX_PIN -1 -#define Y_MIN_PIN PE1 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN PE14 -#define Z_MAX_PIN -1 +#define X_MIN_PIN PE0 +#define X_MAX_PIN -1 +#define Y_MIN_PIN PE1 +#define Y_MAX_PIN -1 +#define Z_MIN_PIN PE14 +#define Z_MAX_PIN -1 // // Z Probe (when not Z_MIN_PIN) @@ -65,120 +65,119 @@ // Steppers // -#define X_STEP_PIN PD3 -#define X_DIR_PIN PD2 -#define X_ENABLE_PIN PD0 +#define X_STEP_PIN PD3 +#define X_DIR_PIN PD2 +#define X_ENABLE_PIN PD0 //#ifndef X_CS_PIN // #define X_CS_PIN PD1 //#endif -#define Y_STEP_PIN PE11 -#define Y_DIR_PIN PE10 -#define Y_ENABLE_PIN PE13 +#define Y_STEP_PIN PE11 +#define Y_DIR_PIN PE10 +#define Y_ENABLE_PIN PE13 //#ifndef Y_CS_PIN // #define Y_CS_PIN PE12 //#endif -#define Z_STEP_PIN PD6 -#define Z_DIR_PIN PD7 -#define Z_ENABLE_PIN PD4 +#define Z_STEP_PIN PD6 +#define Z_DIR_PIN PD7 +#define Z_ENABLE_PIN PD4 //#ifndef Z_CS_PIN // #define Z_CS_PIN PD5 //#endif -#define E0_STEP_PIN PB5 -#define E0_DIR_PIN PB6 -#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PB5 +#define E0_DIR_PIN PB6 +#define E0_ENABLE_PIN PB3 //#ifndef E0_CS_PIN // #define E0_CS_PIN PB4 //#endif -#define E1_STEP_PIN PE4 -#define E1_DIR_PIN PE2 -#define E1_ENABLE_PIN PE3 +#define E1_STEP_PIN PE4 +#define E1_DIR_PIN PE2 +#define E1_ENABLE_PIN PE3 //#ifndef E1_CS_PIN // #define E1_CS_PIN PE5 //#endif -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 +#define SCK_PIN PA5 +#define MISO_PIN PA6 +#define MOSI_PIN PA7 // // Temperature Sensors // -#define TEMP_0_PIN PC0 // Analog Input -#define TEMP_1_PIN PC1 // Analog Input -#define TEMP_BED_PIN PC2 // Analog Input +#define TEMP_0_PIN PC0 // Analog Input +#define TEMP_1_PIN PC1 // Analog Input +#define TEMP_BED_PIN PC2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PA1 -#define HEATER_1_PIN PA2 -#define HEATER_BED_PIN PA0 +#define HEATER_0_PIN PA1 +#define HEATER_1_PIN PA2 +#define HEATER_BED_PIN PA0 #ifndef FAN_PIN - #define FAN_PIN PC6 + #define FAN_PIN PC6 #endif -#define FAN1_PIN PC7 -#define FAN2_PIN PC8 +#define FAN1_PIN PC7 +#define FAN2_PIN PC8 -#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN // Use this by NOT overriding E0_AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN // Use this by NOT overriding E0_AUTO_FAN_PIN // // Misc. Functions // -//#define CASE_LIGHT_PIN_CI PF13 -//#define CASE_LIGHT_PIN_DO PF14 -//#define NEOPIXEL_PIN PF13 +//#define CASE_LIGHT_PIN_CI PF13 +//#define CASE_LIGHT_PIN_DO PF14 +//#define NEOPIXEL_PIN PF13 // // Průša i3 MK2 Multi Material Multiplexer Support // -//#define E_MUX0_PIN PG3 -//#define E_MUX1_PIN PG4 +//#define E_MUX0_PIN PG3 +//#define E_MUX1_PIN PG4 // // Servos // -//#define SERVO0_PIN PE13 -//#define SERVO1_PIN PE14 +//#define SERVO0_PIN PE13 +//#define SERVO1_PIN PE14 - -#define SDSS PE7 -#define SS_PIN PE7 -#define LED_PIN PB7 //Alive -#define PS_ON_PIN PA10 -#define KILL_PIN PA8 -#define PWR_LOSS PA4 //Power loss / nAC_FAULT +#define SDSS PE7 +#define SS_PIN PE7 +#define LED_PIN PB7 //Alive +#define PS_ON_PIN PA10 +#define KILL_PIN PA8 +#define PWR_LOSS PA4 //Power loss / nAC_FAULT // // LCD / Controller // -#define SD_DETECT_PIN PA15 -#define BEEPER_PIN PC9 -#define LCD_PINS_RS PE9 -#define LCD_PINS_ENABLE PE8 -#define LCD_PINS_D4 PB12 -#define LCD_PINS_D5 PB13 -#define LCD_PINS_D6 PB14 -#define LCD_PINS_D7 PB15 -#define BTN_EN1 PC4 -#define BTN_EN2 PC5 -#define BTN_ENC PC3 +#define SD_DETECT_PIN PA15 +#define BEEPER_PIN PC9 +#define LCD_PINS_RS PE9 +#define LCD_PINS_ENABLE PE8 +#define LCD_PINS_D4 PB12 +#define LCD_PINS_D5 PB13 +#define LCD_PINS_D6 PB14 +#define LCD_PINS_D7 PB15 +#define BTN_EN1 PC4 +#define BTN_EN2 PC5 +#define BTN_ENC PC3 // // Filament runout // -#define FIL_RUNOUT_PIN PA3 +#define FIL_RUNOUT_PIN PA3 // // ST7920 Delays diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 2b3ad60199..d21cdd0958 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -35,14 +35,14 @@ // // Servos // -//#define SERVO0_PIN PD12 +//#define SERVO0_PIN PD12 // // Limit Switches // -#define X_STOP_PIN PG3 -#define Y_STOP_PIN PG4 -#define Z_STOP_PIN PG5 +#define X_STOP_PIN PG3 +#define Y_STOP_PIN PG4 +#define Z_STOP_PIN PG5 // // Z Probe (when not Z_MIN_PIN) @@ -54,43 +54,43 @@ // // Filament runout // -#define FIL_RUNOUT_PIN PE6 -#define FIL_RUNOUT2_PIN PE7 +#define FIL_RUNOUT_PIN PE6 +#define FIL_RUNOUT2_PIN PE7 // // Steppers // -#define X_STEP_PIN PG1 -#define X_DIR_PIN PB10 -#define X_ENABLE_PIN PG0 +#define X_STEP_PIN PG1 +#define X_DIR_PIN PB10 +#define X_ENABLE_PIN PG0 //#ifndef X_CS_PIN // #define X_CS_PIN PE0 //#endif -#define Y_STEP_PIN PF14 -#define Y_DIR_PIN PF15 -#define Y_ENABLE_PIN PF13 +#define Y_STEP_PIN PF14 +#define Y_DIR_PIN PF15 +#define Y_ENABLE_PIN PF13 //#ifndef Y_CS_PIN // #define Y_CS_PIN PE1 //#endif -#define Z_STEP_PIN PF11 -#define Z_DIR_PIN PF12 -#define Z_ENABLE_PIN PC5 +#define Z_STEP_PIN PF11 +#define Z_DIR_PIN PF12 +#define Z_ENABLE_PIN PC5 //#ifndef Z_CS_PIN // #define Z_CS_PIN PE2 //#endif -#define E0_STEP_PIN PC14 -#define E0_DIR_PIN PC13 -#define E0_ENABLE_PIN PC15 +#define E0_STEP_PIN PC14 +#define E0_DIR_PIN PC13 +#define E0_ENABLE_PIN PC15 //#ifndef E0_CS_PIN // #define E0_CS_PIN PE3 //#endif -#define E1_STEP_PIN PF1 -#define E1_DIR_PIN PF0 -#define E1_ENABLE_PIN PF2 +#define E1_STEP_PIN PF1 +#define E1_DIR_PIN PF0 +#define E1_ENABLE_PIN PF2 //#ifndef E1_CS_PIN // #define E1_CS_PIN PE4 //#endif @@ -98,37 +98,37 @@ // // Temperature Sensors // -#define TEMP_0_PIN PC1 // Analog Input -#define TEMP_1_PIN PC2 // Analog Input -#define TEMP_BED_PIN PC0 // Analog Input +#define TEMP_0_PIN PC1 // Analog Input +#define TEMP_1_PIN PC2 // Analog Input +#define TEMP_BED_PIN PC0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PA1 -#define HEATER_1_PIN PA0 -#define HEATER_BED_PIN PA2 +#define HEATER_0_PIN PA1 +#define HEATER_1_PIN PA0 +#define HEATER_BED_PIN PA2 #ifndef FAN_PIN - #define FAN_PIN PC15 + #define FAN_PIN PC15 #endif -#define FAN1_PIN PF6 -#define FAN2_PIN PF7 +#define FAN1_PIN PF6 +#define FAN2_PIN PF7 -#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN // Use this by NOT overriding E0_AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN // Use this by NOT overriding E0_AUTO_FAN_PIN // // LED / Lighting // -//#define CASE_LIGHT_PIN_CI -1 -//#define CASE_LIGHT_PIN_DO -1 -//#define NEOPIXEL_PIN -1 +//#define CASE_LIGHT_PIN_CI -1 +//#define CASE_LIGHT_PIN_DO -1 +//#define NEOPIXEL_PIN -1 // // Prusa i3 MK2 Multi-Material Multiplexer Support // -//#define E_MUX0_PIN -1 -//#define E_MUX1_PIN -1 +//#define E_MUX0_PIN -1 +//#define E_MUX1_PIN -1 // // SD support @@ -138,34 +138,34 @@ // // Misc. Functions // -#define SDSS PC11 -#define LED_PIN PC7 // Alive -#define PS_ON_PIN -1 -#define KILL_PIN -1 -#define POWER_LOSS_PIN -1 // Power-loss / nAC_FAULT +#define SDSS PC11 +#define LED_PIN PC7 // Alive +#define PS_ON_PIN -1 +#define KILL_PIN -1 +#define POWER_LOSS_PIN -1 // Power-loss / nAC_FAULT -#define SCK_PIN PC12 -#define MISO_PIN PC8 -#define MOSI_PIN PD2 -#define SS_PIN PC11 +#define SCK_PIN PC12 +#define MISO_PIN PC8 +#define MOSI_PIN PD2 +#define SS_PIN PC11 // // LCD / Controller // // TODO: Replace these with the correct FSMC pins, once known -#define SD_DETECT_PIN -1 -#define BEEPER_PIN PD12 -#define LCD_PINS_RS -1 -#define LCD_PINS_ENABLE -1 -#define LCD_PINS_D4 -1 -#define LCD_PINS_D5 -1 -#define LCD_PINS_D6 -1 -#define LCD_PINS_D7 -1 +#define SD_DETECT_PIN -1 +#define BEEPER_PIN PD12 +#define LCD_PINS_RS -1 +#define LCD_PINS_ENABLE -1 +#define LCD_PINS_D4 -1 +#define LCD_PINS_D5 -1 +#define LCD_PINS_D6 -1 +#define LCD_PINS_D7 -1 -#define BTN_EN1 PE3 -#define BTN_EN2 PE4 -#define BTN_ENC PE2 +#define BTN_EN1 PE3 +#define BTN_EN2 PE4 +#define BTN_ENC PE2 // // ST7920 Delays diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index f498b7d0b9..c54c5c1806 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -32,20 +32,20 @@ // // Servos // -//#define SERVO0_PIN PD12 -//#define SERVO1_PIN -1 +//#define SERVO0_PIN PD12 +//#define SERVO1_PIN -1 // // Limit Switches // -#define X_STOP_PIN PB12 -#define Y_STOP_PIN PB13 -#define Z_STOP_PIN PB14 +#define X_STOP_PIN PB12 +#define Y_STOP_PIN PB13 +#define Z_STOP_PIN PB14 // // Filament runout // -#define FIL_RUNOUT_PIN PE1 +#define FIL_RUNOUT_PIN PE1 // // Z Probe (when not Z_MIN_PIN) @@ -57,37 +57,37 @@ // // Steppers // -#define X_STEP_PIN PB10 -#define X_DIR_PIN PB2 -#define X_ENABLE_PIN PB11 +#define X_STEP_PIN PB10 +#define X_DIR_PIN PB2 +#define X_ENABLE_PIN PB11 //#ifndef X_CS_PIN // #define X_CS_PIN PD1 //#endif -#define Y_STEP_PIN PB0 -#define Y_DIR_PIN PC5 -#define Y_ENABLE_PIN PB1 +#define Y_STEP_PIN PB0 +#define Y_DIR_PIN PC5 +#define Y_ENABLE_PIN PB1 //#ifndef Y_CS_PIN // #define Y_CS_PIN PE12 //#endif -#define Z_STEP_PIN PA7 -#define Z_DIR_PIN PA6 -#define Z_ENABLE_PIN PC4 +#define Z_STEP_PIN PA7 +#define Z_DIR_PIN PA6 +#define Z_ENABLE_PIN PC4 //#ifndef Z_CS_PIN // #define Z_CS_PIN PD5 //#endif -#define E0_STEP_PIN PA4 -#define E0_DIR_PIN PA3 -#define E0_ENABLE_PIN PA5 +#define E0_STEP_PIN PA4 +#define E0_DIR_PIN PA3 +#define E0_ENABLE_PIN PA5 //#ifndef E0_CS_PIN // #define E0_CS_PIN PB4 //#endif -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 //#ifndef E1_CS_PIN // #define E1_CS_PIN PE5 //#endif @@ -95,51 +95,51 @@ // // Temperature Sensors // -#define TEMP_0_PIN PC0 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_BED_PIN PC1 // Analog Input +#define TEMP_0_PIN PC0 // Analog Input +#define TEMP_1_PIN -1 // Analog Input +#define TEMP_BED_PIN PC1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PA1 -#define HEATER_1_PIN -1 -#define HEATER_BED_PIN PA2 +#define HEATER_0_PIN PA1 +#define HEATER_1_PIN -1 +#define HEATER_BED_PIN PA2 #ifndef FAN_PIN // #define FAN_PIN PC15 #endif -#define FAN1_PIN PC15 -#define FAN2_PIN PA0 +#define FAN1_PIN PC15 +#define FAN2_PIN PA0 -#define ORIG_E0_AUTO_FAN_PIN PC15 // Use this by NOT overriding E0_AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN PC15 // Use this by NOT overriding E0_AUTO_FAN_PIN // // Prusa i3 MK2 Multi Material Multiplexer Support // -//#define E_MUX0_PIN -1 -//#define E_MUX1_PIN -1 +//#define E_MUX0_PIN -1 +//#define E_MUX1_PIN -1 // // LED / Lighting // -//#define CASE_LIGHT_PIN_CI -1 -//#define CASE_LIGHT_PIN_DO -1 -//#define NEOPIXEL_PIN -1 +//#define CASE_LIGHT_PIN_CI -1 +//#define CASE_LIGHT_PIN_DO -1 +//#define NEOPIXEL_PIN -1 // // Misc. Functions // -#define SDSS PC11 -#define LED_PIN PC7 // Alive -#define PS_ON_PIN -1 -#define KILL_PIN -1 -#define POWER_LOSS_PIN -1 // Power-loss / nAC_FAULT +#define SDSS PC11 +#define LED_PIN PC7 // Alive +#define PS_ON_PIN -1 +#define KILL_PIN -1 +#define POWER_LOSS_PIN -1 // Power-loss / nAC_FAULT -#define SCK_PIN PC12 -#define MISO_PIN PC8 -#define MOSI_PIN PD2 -#define SS_PIN PC11 +#define SCK_PIN PC12 +#define MISO_PIN PC8 +#define MOSI_PIN PD2 +#define SS_PIN PC11 // // SD support @@ -151,18 +151,18 @@ // // The LCD is initialized in FSMC mode -#define SD_DETECT_PIN -1 -#define BEEPER_PIN PD12 +#define SD_DETECT_PIN -1 +#define BEEPER_PIN PD12 -#define BTN_EN1 PE3 -#define BTN_EN2 PE4 -#define BTN_ENC PE2 +#define BTN_EN1 PE3 +#define BTN_EN2 PE4 +#define BTN_ENC PE2 -#define LCD_RESET_PIN PD6 -#define LCD_BACKLIGHT_PIN PD3 -#define FSMC_CS_PIN PD4 -#define FSMC_RS_PIN PD11 -#define TOUCH_CS PB6 +#define LCD_RESET_PIN PD6 +#define LCD_BACKLIGHT_PIN PD3 +#define FSMC_CS_PIN PD4 +#define FSMC_RS_PIN PD11 +#define TOUCH_CS PB6 // // ST7920 Delays diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h index 5d97de12eb..36298d05f5 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h @@ -40,63 +40,62 @@ // // Limit Switches // -#define X_MIN_PIN PG8 -#define X_MAX_PIN PG7 -#define Y_MIN_PIN PG6 -#define Y_MAX_PIN PG5 -#define Z_MIN_PIN PG4 -#define Z_MAX_PIN PG3 +#define X_MIN_PIN PG8 +#define X_MAX_PIN PG7 +#define Y_MIN_PIN PG6 +#define Y_MAX_PIN PG5 +#define Z_MIN_PIN PG4 +#define Z_MAX_PIN PG3 // // Servos // -#define SERVO0_PIN PB0 // XS2-5 -#define SERVO1_PIN PF7 // XS1-5 -#define SERVO2_PIN PF8 // XS1-6 +#define SERVO0_PIN PB0 // XS2-5 +#define SERVO1_PIN PF7 // XS1-5 +#define SERVO2_PIN PF8 // XS1-6 // // Steppers // -#define X_STEP_PIN PE6 -#define X_DIR_PIN PE5 -#define X_ENABLE_PIN PC13 +#define X_STEP_PIN PE6 +#define X_DIR_PIN PE5 +#define X_ENABLE_PIN PC13 -#define Y_STEP_PIN PE3 -#define Y_DIR_PIN PE2 -#define Y_ENABLE_PIN PE4 +#define Y_STEP_PIN PE3 +#define Y_DIR_PIN PE2 +#define Y_ENABLE_PIN PE4 -#define Z_STEP_PIN PE0 -#define Z_DIR_PIN PB9 -#define Z_ENABLE_PIN PE1 +#define Z_STEP_PIN PE0 +#define Z_DIR_PIN PB9 +#define Z_ENABLE_PIN PE1 -#define E0_STEP_PIN PG10 -#define E0_DIR_PIN PG9 -#define E0_ENABLE_PIN PB8 - -#define E1_STEP_PIN PD3 -#define E1_DIR_PIN PA15 -#define E1_ENABLE_PIN PD6 +#define E0_STEP_PIN PG10 +#define E0_DIR_PIN PG9 +#define E0_ENABLE_PIN PB8 +#define E1_STEP_PIN PD3 +#define E1_DIR_PIN PA15 +#define E1_ENABLE_PIN PD6 // // Temperature Sensors // -#define TEMP_0_PIN PC1 // T1 <-> E0 -#define TEMP_1_PIN PC2 // T2 <-> E1 -#define TEMP_BED_PIN PC0 // T0 <-> Bed +#define TEMP_0_PIN PC1 // T1 <-> E0 +#define TEMP_1_PIN PC2 // T2 <-> E1 +#define TEMP_BED_PIN PC0 // T0 <-> Bed // // Heaters / Fans // -#define HEATER_0_PIN PF3 // Heater0 -#define HEATER_1_PIN PF2 // Heater1 -#define HEATER_BED_PIN PF4 // Hotbed -#define FAN_PIN PA7 // Fan0 +#define HEATER_0_PIN PF3 // Heater0 +#define HEATER_1_PIN PF2 // Heater1 +#define HEATER_BED_PIN PF4 // Hotbed +#define FAN_PIN PA7 // Fan0 // // Misc. Functions // -#define SDSS -1 // PB12 +#define SDSS -1 // PB12 -#define SD_DETECT_PIN PF9 -#define BEEPER_PIN PG2 +#define SD_DETECT_PIN PF9 +#define BEEPER_PIN PG2 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h index a6bc2b49a6..9fcd5a1474 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h @@ -46,13 +46,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 + #define TMC_SW_MOSI PA7 #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 + #define TMC_SW_MISO PA6 #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 + #define TMC_SW_SCK PA5 #endif #endif @@ -78,23 +78,23 @@ // // Software serial // - #define X_SERIAL_TX_PIN PA3 - #define X_SERIAL_RX_PIN PC14 + #define X_SERIAL_TX_PIN PA3 + #define X_SERIAL_RX_PIN PC14 - #define Y_SERIAL_TX_PIN PA4 - #define Y_SERIAL_RX_PIN PE4 + #define Y_SERIAL_TX_PIN PA4 + #define Y_SERIAL_RX_PIN PE4 - #define Z_SERIAL_TX_PIN PD13 - #define Z_SERIAL_RX_PIN PE0 + #define Z_SERIAL_TX_PIN PD13 + #define Z_SERIAL_RX_PIN PE0 - #define E0_SERIAL_TX_PIN PD14 - #define E0_SERIAL_RX_PIN PC13 + #define E0_SERIAL_TX_PIN PD14 + #define E0_SERIAL_RX_PIN PC13 - #define E1_SERIAL_TX_PIN PD15 - #define E1_SERIAL_RX_PIN PD5 + #define E1_SERIAL_TX_PIN PD15 + #define E1_SERIAL_RX_PIN PD5 - #define E2_SERIAL_TX_PIN PD12 - #define E2_SERIAL_RX_PIN PD1 + #define E2_SERIAL_TX_PIN PD12 + #define E2_SERIAL_RX_PIN PD1 #endif // diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 0fb469112d..19853a78fe 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -38,112 +38,112 @@ #ifdef E2END #undef E2END #endif -#define E2END 0xFFF // 4KB +#define E2END 0xFFF // 4KB // // Limit Switches // -#define X_MIN_PIN PB12 -#define X_MAX_PIN PB13 -#define Y_MIN_PIN PB15 -#define Y_MAX_PIN PD8 -#define Z_MIN_PIN PD9 -#define Z_MAX_PIN PD10 +#define X_MIN_PIN PB12 +#define X_MAX_PIN PB13 +#define Y_MIN_PIN PB15 +#define Y_MAX_PIN PD8 +#define Z_MIN_PIN PD9 +#define Z_MAX_PIN PD10 // // Steppers // -#define X_STEP_PIN PA0 -#define X_DIR_PIN PC15 -#define X_ENABLE_PIN PC11 -#define X_CS_PIN PC14 +#define X_STEP_PIN PA0 +#define X_DIR_PIN PC15 +#define X_ENABLE_PIN PC11 +#define X_CS_PIN PC14 -#define Y_STEP_PIN PE5 -#define Y_DIR_PIN PE6 -#define Y_ENABLE_PIN PE3 -#define Y_CS_PIN PE4 +#define Y_STEP_PIN PE5 +#define Y_DIR_PIN PE6 +#define Y_ENABLE_PIN PE3 +#define Y_CS_PIN PE4 -#define Z_STEP_PIN PE1 -#define Z_DIR_PIN PE2 -#define Z_ENABLE_PIN PB7 -#define Z_CS_PIN PE0 +#define Z_STEP_PIN PE1 +#define Z_DIR_PIN PE2 +#define Z_ENABLE_PIN PB7 +#define Z_CS_PIN PE0 -#define E0_STEP_PIN PB5 -#define E0_DIR_PIN PB6 -#define E0_ENABLE_PIN PC12 -#define E0_CS_PIN PC13 +#define E0_STEP_PIN PB5 +#define E0_DIR_PIN PB6 +#define E0_ENABLE_PIN PC12 +#define E0_CS_PIN PC13 -#define E1_STEP_PIN PD6 -#define E1_DIR_PIN PD7 -#define E1_ENABLE_PIN PD4 -#define E1_CS_PIN PD5 +#define E1_STEP_PIN PD6 +#define E1_DIR_PIN PD7 +#define E1_ENABLE_PIN PD4 +#define E1_CS_PIN PD5 -#define E2_STEP_PIN PD2 -#define E2_DIR_PIN PD3 -#define E2_ENABLE_PIN PD0 -#define E2_CS_PIN PD1 +#define E2_STEP_PIN PD2 +#define E2_DIR_PIN PD3 +#define E2_ENABLE_PIN PD0 +#define E2_CS_PIN PD1 // // Temperature Sensors // -#define TEMP_0_PIN PC4 -#define TEMP_1_PIN PC3 -#define TEMP_2_PIN PC2 -#define TEMP_3_PIN PC1 -#define TEMP_BED_PIN PC0 +#define TEMP_0_PIN PC4 +#define TEMP_1_PIN PC3 +#define TEMP_2_PIN PC2 +#define TEMP_3_PIN PC1 +#define TEMP_BED_PIN PC0 // // Heaters / Fans // -#define HEATER_0_PIN PC6 -#define HEATER_1_PIN PC7 -#define HEATER_2_PIN PC8 -#define HEATER_BED_PIN PA1 +#define HEATER_0_PIN PC6 +#define HEATER_1_PIN PC7 +#define HEATER_2_PIN PC8 +#define HEATER_BED_PIN PA1 -#define FAN_PIN PC9 -#define FAN1_PIN PA8 +#define FAN_PIN PC9 +#define FAN1_PIN PA8 // // I2C // -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 +#define SCK_PIN PA5 +#define MISO_PIN PA6 +#define MOSI_PIN PA7 // // Misc. Functions // -#define LED_PIN PB14 -#define BTN_PIN PC10 -#define PS_ON_PIN PE11 -#define KILL_PIN PC5 +#define LED_PIN PB14 +#define BTN_PIN PC10 +#define PS_ON_PIN PE11 +#define KILL_PIN PC5 -#define SDSS PA2 -#define SD_DETECT_PIN PB0 -#define BEEPER_PIN PE8 +#define SDSS PA2 +#define SD_DETECT_PIN PB0 +#define BEEPER_PIN PE8 // // LCD / Controller // #if HAS_SPI_LCD - #define BTN_EN1 PB2 - #define BTN_EN2 PB1 - #define BTN_ENC PE7 + #define BTN_EN1 PB2 + #define BTN_EN2 PB1 + #define BTN_ENC PE7 - #define LCD_PINS_RS PE10 - #define LCD_PINS_ENABLE PE9 - #define LCD_PINS_D4 PE12 + #define LCD_PINS_RS PE10 + #define LCD_PINS_ENABLE PE9 + #define LCD_PINS_D4 PE12 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS PE13 - #define DOGLCD_A0 PE14 + #define DOGLCD_CS PE13 + #define DOGLCD_A0 PE14 #endif #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PE13 - #define LCD_PINS_D6 PE14 - #define LCD_PINS_D7 PE15 + #define LCD_PINS_D5 PE13 + #define LCD_PINS_D6 PE14 + #define LCD_PINS_D7 PE15 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 2b6e6f6c33..1a008cd4ae 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -51,13 +51,13 @@ // // Limit Switches // -#define X_MIN_PIN 39 // PD8 X_STOP -#define Y_MIN_PIN 40 // PD9 Y_STOP -#define Z_MIN_PIN 41 // PD10 Z_STOP +#define X_MIN_PIN 39 // PD8 X_STOP +#define Y_MIN_PIN 40 // PD9 Y_STOP +#define Z_MIN_PIN 41 // PD10 Z_STOP -#define X_MAX_PIN 44 // PD0 W_STOP -#define Y_MAX_PIN 43 // PA8 V_STOP -#define Z_MAX_PIN 42 // PD11 U_STOP +#define X_MAX_PIN 44 // PD0 W_STOP +#define Y_MAX_PIN 43 // PA8 V_STOP +#define Z_MAX_PIN 42 // PD11 U_STOP // // Z Probe (when not Z_MIN_PIN) @@ -69,64 +69,64 @@ // // Filament runout // -//#define FIL_RUNOUT_PIN 53 // PA3 BED_THE +//#define FIL_RUNOUT_PIN 53 // PA3 BED_THE // // Steppers // -#define X_STEP_PIN 61 // PE14 X_PWM -#define X_DIR_PIN 62 // PE15 X_DIR -#define X_ENABLE_PIN 60 // PE13 X_RES -#define X_CS_PIN 16 // PA4 SPI_CS +#define X_STEP_PIN 61 // PE14 X_PWM +#define X_DIR_PIN 62 // PE15 X_DIR +#define X_ENABLE_PIN 60 // PE13 X_RES +#define X_CS_PIN 16 // PA4 SPI_CS -#define Y_STEP_PIN 64 // PB10 Y_PWM -#define Y_DIR_PIN 65 // PE9 Y_DIR -#define Y_ENABLE_PIN 63 // PE10 Y_RES -#define Y_CS_PIN 16 // PA4 SPI_CS +#define Y_STEP_PIN 64 // PB10 Y_PWM +#define Y_DIR_PIN 65 // PE9 Y_DIR +#define Y_ENABLE_PIN 63 // PE10 Y_RES +#define Y_CS_PIN 16 // PA4 SPI_CS -#define Z_STEP_PIN 67 // PC6 Z_PWM -#define Z_DIR_PIN 68 // PC0 Z_DIR -#define Z_ENABLE_PIN 66 // PC15 Z_RES -#define Z_CS_PIN 16 // PA4 SPI_CS +#define Z_STEP_PIN 67 // PC6 Z_PWM +#define Z_DIR_PIN 68 // PC0 Z_DIR +#define Z_ENABLE_PIN 66 // PC15 Z_RES +#define Z_CS_PIN 16 // PA4 SPI_CS -#define E0_STEP_PIN 71 // PD12 E1_PW -#define E0_DIR_PIN 70 // PC13 E1_DIR -#define E0_ENABLE_PIN 69 // PC14 E1_RE -#define E0_CS_PIN 16 // PA4 SPI_CS +#define E0_STEP_PIN 71 // PD12 E1_PW +#define E0_DIR_PIN 70 // PC13 E1_DIR +#define E0_ENABLE_PIN 69 // PC14 E1_RE +#define E0_CS_PIN 16 // PA4 SPI_CS -#define E1_STEP_PIN 73 // PE5 E2_PWM -#define E1_DIR_PIN 74 // PE6 E2_DIR -#define E1_ENABLE_PIN 72 // PE4 E2_RESE -#define E1_CS_PIN 16 // PA4 SPI_CS +#define E1_STEP_PIN 73 // PE5 E2_PWM +#define E1_DIR_PIN 74 // PE6 E2_DIR +#define E1_ENABLE_PIN 72 // PE4 E2_RESE +#define E1_CS_PIN 16 // PA4 SPI_CS -#define E2_STEP_PIN 77 // PB8 E3_PWM -#define E2_DIR_PIN 76 // PE2 E3_DIR -#define E2_ENABLE_PIN 75 // PE3 E3_RESE -#define E2_CS_PIN 16 // PA4 SPI_CS +#define E2_STEP_PIN 77 // PB8 E3_PWM +#define E2_DIR_PIN 76 // PE2 E3_DIR +#define E2_ENABLE_PIN 75 // PE3 E3_RESE +#define E2_CS_PIN 16 // PA4 SPI_CS // needed to pass a sanity check -#define X2_CS_PIN 16 // PA4 SPI_CS -#define Y2_CS_PIN 16 // PA4 SPI_CS -#define Z2_CS_PIN 16 // PA4 SPI_CS -#define Z3_CS_PIN 16 // PA4 SPI_CS -#define E3_CS_PIN 16 // PA4 SPI_CS -#define E4_CS_PIN 16 // PA4 SPI_CS -#define E5_CS_PIN 16 // PA4 SPI_CS +#define X2_CS_PIN 16 // PA4 SPI_CS +#define Y2_CS_PIN 16 // PA4 SPI_CS +#define Z2_CS_PIN 16 // PA4 SPI_CS +#define Z3_CS_PIN 16 // PA4 SPI_CS +#define E3_CS_PIN 16 // PA4 SPI_CS +#define E4_CS_PIN 16 // PA4 SPI_CS +#define E5_CS_PIN 16 // PA4 SPI_CS #if HAS_L64XX - #define L6470_CHAIN_SCK_PIN 17 // PA5 - #define L6470_CHAIN_MISO_PIN 18 // PA6 - #define L6470_CHAIN_MOSI_PIN 19 // PA7 - #define L6470_CHAIN_SS_PIN 16 // PA4 + #define L6470_CHAIN_SCK_PIN 17 // PA5 + #define L6470_CHAIN_MISO_PIN 18 // PA6 + #define L6470_CHAIN_MOSI_PIN 19 // PA7 + #define L6470_CHAIN_SS_PIN 16 // PA4 - //#define SCK_PIN L6470_CHAIN_SCK_PIN - //#define MISO_PIN L6470_CHAIN_MISO_PIN - //#define MOSI_PIN L6470_CHAIN_MOSI_PIN + //#define SCK_PIN L6470_CHAIN_SCK_PIN + //#define MISO_PIN L6470_CHAIN_MISO_PIN + //#define MOSI_PIN L6470_CHAIN_MOSI_PIN #else - //#define SCK_PIN 13 // PB13 SPI_S - //#define MISO_PIN 12 // PB14 SPI_M - //#define MOSI_PIN 11 // PB15 SPI_M + //#define SCK_PIN 13 // PB13 SPI_S + //#define MISO_PIN 12 // PB14 SPI_M + //#define MOSI_PIN 11 // PB15 SPI_M #endif /** @@ -147,64 +147,64 @@ // // Temperature Sensors // -#define TEMP_0_PIN 3 // Analog input 3, digital pin 54 PA0 E1_THERMISTOR -#define TEMP_1_PIN 4 // Analog input 4, digital pin 55 PA1 E2_THERMISTOR -#define TEMP_2_PIN 5 // Analog input 5, digital pin 56 PA2 E3_THERMISTOR -#define TEMP_BED_PIN 0 // Analog input 0, digital pin 51 PC2 BED_THERMISTOR_1 -#define TEMP_BED_1_PIN 1 // Analog input 1, digital pin 52 PC3 BED_THERMISTOR_2 -#define TEMP_BED_2_PIN 2 // Analog input 2, digital pin 53 PA3 BED_THERMISTOR_3 +#define TEMP_0_PIN 3 // Analog input 3, digital pin 54 PA0 E1_THERMISTOR +#define TEMP_1_PIN 4 // Analog input 4, digital pin 55 PA1 E2_THERMISTOR +#define TEMP_2_PIN 5 // Analog input 5, digital pin 56 PA2 E3_THERMISTOR +#define TEMP_BED_PIN 0 // Analog input 0, digital pin 51 PC2 BED_THERMISTOR_1 +#define TEMP_BED_1_PIN 1 // Analog input 1, digital pin 52 PC3 BED_THERMISTOR_2 +#define TEMP_BED_2_PIN 2 // Analog input 2, digital pin 53 PA3 BED_THERMISTOR_3 // // Heaters / Fans // -#define HEATER_0_PIN 48 // PC7 E1_HEAT_PWM -#define HEATER_1_PIN 49 // PB0 E2_HEAT_PWM -#define HEATER_2_PIN 50 // PB1 E3_HEAT_PWM -#define HEATER_BED_PIN 46 // PD14 (BED_HEAT_1 FET -#define HEATER_BED_1_PIN 45 // PD13 (BED_HEAT_2 FET -#define HEATER_BED_2_PIN 47 // PD15 (BED_HEAT_3 FET +#define HEATER_0_PIN 48 // PC7 E1_HEAT_PWM +#define HEATER_1_PIN 49 // PB0 E2_HEAT_PWM +#define HEATER_2_PIN 50 // PB1 E3_HEAT_PWM +#define HEATER_BED_PIN 46 // PD14 (BED_HEAT_1 FET +#define HEATER_BED_1_PIN 45 // PD13 (BED_HEAT_2 FET +#define HEATER_BED_2_PIN 47 // PD15 (BED_HEAT_3 FET -#define FAN_PIN 57 // PC4 E1_FAN PWM pin, Part cooling fan FET -#define FAN1_PIN 58 // PC5 E2_FAN PWM pin, Extruder fan FET -#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN -#define FAN2_PIN 59 // PE8 E3_FAN PWM pin, Controller fan FET +#define FAN_PIN 57 // PC4 E1_FAN PWM pin, Part cooling fan FET +#define FAN1_PIN 58 // PC5 E2_FAN PWM pin, Extruder fan FET +#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN +#define FAN2_PIN 59 // PE8 E3_FAN PWM pin, Controller fan FET // // Misc functions // -#define SDSS 16 // PA4 SPI_CS -#define LED_PIN -1 // 9 // PE1 green LED Heart beat -#define PS_ON_PIN -1 -#define KILL_PIN -1 -#define POWER_LOSS_PIN -1 // PWR_LOSS / nAC_FAULT +#define SDSS 16 // PA4 SPI_CS +#define LED_PIN -1 // 9 // PE1 green LED Heart beat +#define PS_ON_PIN -1 +#define KILL_PIN -1 +#define POWER_LOSS_PIN -1 // PWR_LOSS / nAC_FAULT // // LCD / Controller // -//#define SD_DETECT_PIN 66 // PA15 SD_CA -//#define BEEPER_PIN 24 // PC9 SDIO_D1 -//#define LCD_PINS_RS 65 // PE9 Y_DIR -//#define LCD_PINS_ENABLE 59 // PE8 E3_FAN -//#define LCD_PINS_D4 10 // PB12 SPI_C -//#define LCD_PINS_D5 13 // PB13 SPI_S -//#define LCD_PINS_D6 12 // PB14 SPI_M -//#define LCD_PINS_D7 11 // PB15 SPI_M -//#define BTN_EN1 57 // PC4 E1_FAN -//#define BTN_EN2 58 // PC5 E2_FAN -//#define BTN_ENC 52 // PC3 BED_THE +//#define SD_DETECT_PIN 66 // PA15 SD_CA +//#define BEEPER_PIN 24 // PC9 SDIO_D1 +//#define LCD_PINS_RS 65 // PE9 Y_DIR +//#define LCD_PINS_ENABLE 59 // PE8 E3_FAN +//#define LCD_PINS_D4 10 // PB12 SPI_C +//#define LCD_PINS_D5 13 // PB13 SPI_S +//#define LCD_PINS_D6 12 // PB14 SPI_M +//#define LCD_PINS_D7 11 // PB15 SPI_M +//#define BTN_EN1 57 // PC4 E1_FAN +//#define BTN_EN2 58 // PC5 E2_FAN +//#define BTN_ENC 52 // PC3 BED_THE // // Extension pins // -//#define EXT0_PIN 49 // PB0 E2_HEAT -//#define EXT1_PIN 50 // PB1 E3_HEAT -//#define EXT2_PIN // PB2 not used (tied to ground -//#define EXT3_PIN 39 // PD8 X_STOP -//#define EXT4_PIN 40 // PD9 Y_STOP -//#define EXT5_PIN 41 // PD10 Z_STOP -//#define EXT6_PIN 42 // PD11 -//#define EXT7_PIN 71 // PD12 E1_PW -//#define EXT8_PIN 64 // PB10 Y_PWM +//#define EXT0_PIN 49 // PB0 E2_HEAT +//#define EXT1_PIN 50 // PB1 E3_HEAT +//#define EXT2_PIN // PB2 not used (tied to ground +//#define EXT3_PIN 39 // PD8 X_STOP +//#define EXT4_PIN 40 // PD9 Y_STOP +//#define EXT5_PIN 41 // PD10 Z_STOP +//#define EXT6_PIN 42 // PD11 +//#define EXT7_PIN 71 // PD12 E1_PW +//#define EXT8_PIN 64 // PB10 Y_PWM // WIFI // 2 // PD3 CTS @@ -215,7 +215,6 @@ // 7 // PE11 WIFI_RESET // 8 // PE12 WIFI_BOOT - // I2C USER // 14 // PB7 SDA // 15 // PB6 SCL @@ -228,27 +227,27 @@ // // Onboard SD support // -#define SDIO_D0_PIN 23 // PC8 SDIO_D0 -#define SDIO_D1_PIN 24 // PC9 SDIO_D1 -//#define SD_CARD_DETECT_PIN 25 // PA15 SD_CARD_DETECT -#define SDIO_D2_PIN 26 // PC10 SDIO_D2 -#define SDIO_D3_PIN 27 // PC11 SDIO_D3 -#define SDIO_CK_PIN 28 // PC12 SDIO_CK -#define SDIO_CMD_PIN 29 // PD2 SDIO_CMD +#define SDIO_D0_PIN 23 // PC8 SDIO_D0 +#define SDIO_D1_PIN 24 // PC9 SDIO_D1 +//#define SD_CARD_DETECT_PIN 25 // PA15 SD_CARD_DETECT +#define SDIO_D2_PIN 26 // PC10 SDIO_D2 +#define SDIO_D3_PIN 27 // PC11 SDIO_D3 +#define SDIO_CK_PIN 28 // PC12 SDIO_CK +#define SDIO_CMD_PIN 29 // PD2 SDIO_CMD #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SDCARD_CONNECTION == ONBOARD - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT - #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SCK_PIN SDIO_CK_PIN - #define MISO_PIN SDIO_D0_PIN - #define MOSI_PIN SDIO_CMD_PIN + #define SOFTWARE_SPI // Use soft SPI for onboard SD + #define SDSS SDIO_D3_PIN + #define SCK_PIN SDIO_CK_PIN + #define MISO_PIN SDIO_D0_PIN + #define MOSI_PIN SDIO_CMD_PIN #endif #endif @@ -265,16 +264,13 @@ // USERKET // 38 // PE7 USER_BUTTON - // 0 // PA9 TX // 1 // PA10 RX - // IR/PROBE // 32 // PD1 IR_OUT // 33 // PC1 IR_ON - /** * Logical pin vs. port/pin cross reference * diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 35faf076ab..7eb95a4f50 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -32,133 +32,133 @@ //#define I2C_EEPROM -#define E2END 0xFFF // EEPROM end address (4kB) +#define E2END 0xFFF // EEPROM end address (4kB) // // Servos // -//#define SERVO0_PIN PE13 -//#define SERVO1_PIN PE14 +//#define SERVO0_PIN PE13 +//#define SERVO1_PIN PE14 // // Limit Switches // -#define X_STOP_PIN PE10 -#define Y_STOP_PIN PE9 -#define Z_STOP_PIN PE8 +#define X_STOP_PIN PE10 +#define Y_STOP_PIN PE9 +#define Z_STOP_PIN PE8 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PA4 + #define Z_MIN_PROBE_PIN PA4 #endif // // Filament runout // -#define FIL_RUNOUT_PIN PA3 +#define FIL_RUNOUT_PIN PA3 // // Steppers // -#define STEPPER_ENABLE_PIN PB2 +#define STEPPER_ENABLE_PIN PB2 -#define X_STEP_PIN PC6 // X_STEP -#define X_DIR_PIN PC7 // X_DIR -#define X_ENABLE_PIN PB2 // +#define X_STEP_PIN PC6 // X_STEP +#define X_DIR_PIN PC7 // X_DIR +#define X_ENABLE_PIN PB2 // #ifndef X_CS_PIN - #define X_CS_PIN PC8 // X_CS + #define X_CS_PIN PC8 // X_CS #endif -#define Y_STEP_PIN PD9 // Y_STEP -#define Y_DIR_PIN PD10 // Y_DIR -#define Y_ENABLE_PIN PB2 // +#define Y_STEP_PIN PD9 // Y_STEP +#define Y_DIR_PIN PD10 // Y_DIR +#define Y_ENABLE_PIN PB2 // #ifndef Y_CS_PIN - #define Y_CS_PIN PD11 // Y_CS + #define Y_CS_PIN PD11 // Y_CS #endif -#define Z_STEP_PIN PE15 // Z_STEP -#define Z_DIR_PIN PB10 // Z_DIR -#define Z_ENABLE_PIN PB2 +#define Z_STEP_PIN PE15 // Z_STEP +#define Z_DIR_PIN PB10 // Z_DIR +#define Z_ENABLE_PIN PB2 #ifndef Z_CS_PIN - #define Z_CS_PIN PD8 + #define Z_CS_PIN PD8 #endif -#define E0_STEP_PIN PB1 -#define E0_DIR_PIN PB13 -#define E0_ENABLE_PIN PB2 +#define E0_STEP_PIN PB1 +#define E0_DIR_PIN PB13 +#define E0_ENABLE_PIN PB2 #ifndef E0_CS_PIN - #define E0_CS_PIN PE11 + #define E0_CS_PIN PE11 #endif -#define E1_STEP_PIN PC4 -#define E1_DIR_PIN PC5 -#define E1_ENABLE_PIN PB2 +#define E1_STEP_PIN PC4 +#define E1_DIR_PIN PC5 +#define E1_ENABLE_PIN PB2 #ifndef E1_CS_PIN - #define E1_CS_PIN PB0 + #define E1_CS_PIN PB0 #endif -#define SCK_PIN PE12 // PA5 // SPI1 for SD card -#define MISO_PIN PE13 // PA6 -#define MOSI_PIN PE14 // PA7 +#define SCK_PIN PE12 // PA5 // SPI1 for SD card +#define MISO_PIN PE13 // PA6 +#define MOSI_PIN PE14 // PA7 // added for SD card : optional or not ??? -//#define SD_CHIP_SELECT_PIN SDSS // The default chip select pin for the SD card is SS. +//#define SD_CHIP_SELECT_PIN SDSS // The default chip select pin for the SD card is SS. // The following three pins must not be redefined for hardware SPI. -//#define SPI_MOSI_PIN MOSI_PIN // SPI Master Out Slave In pin -//#define SPI_MISO_PIN MISO_PIN // SPI Master In Slave Out pin -//#define SPI_SCK_PIN SCK_PIN // SPI Clock pin +//#define SPI_MOSI_PIN MOSI_PIN // SPI Master Out Slave In pin +//#define SPI_MISO_PIN MISO_PIN // SPI Master In Slave Out pin +//#define SPI_SCK_PIN SCK_PIN // SPI Clock pin // // Temperature Sensors (Analog inputs) // -#define TEMP_0_PIN PC0 // Analog Input -#define TEMP_1_PIN PC1 // Analog Input -#define TEMP_2_PIN PC2 // Analog Input -#define TEMP_3_PIN PC3 // Analog Input -#define TEMP_BED_PIN PC3 // Analog Input +#define TEMP_0_PIN PC0 // Analog Input +#define TEMP_1_PIN PC1 // Analog Input +#define TEMP_2_PIN PC2 // Analog Input +#define TEMP_3_PIN PC3 // Analog Input +#define TEMP_BED_PIN PC3 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PD15 -#define HEATER_1_PIN PD14 -#define HEATER_BED_PIN PD12 +#define HEATER_0_PIN PD15 +#define HEATER_1_PIN PD14 +#define HEATER_BED_PIN PD12 #ifndef FAN_PIN - #define FAN_PIN PD13 + #define FAN_PIN PD13 #endif -#define FAN1_PIN PB5 // PA0 -#define FAN2_PIN PB4 // PA1 +#define FAN1_PIN PB5 // PA0 +#define FAN2_PIN PB4 // PA1 -#define ORIG_E0_AUTO_FAN_PIN PD13 // Use this by NOT overriding E0_AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN PD13 // Use this by NOT overriding E0_AUTO_FAN_PIN // // Misc. Functions // -//#define CASE_LIGHT_PIN_CI PF13 -//#define CASE_LIGHT_PIN_DO PF14 -//#define NEOPIXEL_PIN PF13 +//#define CASE_LIGHT_PIN_CI PF13 +//#define CASE_LIGHT_PIN_DO PF14 +//#define NEOPIXEL_PIN PF13 // // Prusa i3 MK2 Multi Material Multiplexer Support // -//#define E_MUX0_PIN PG3 -//#define E_MUX1_PIN PG4 +//#define E_MUX0_PIN PG3 +//#define E_MUX1_PIN PG4 -#define LED_PIN PB14 // Alive -#define PS_ON_PIN PE0 -#define KILL_PIN PD5 -#define POWER_LOSS_PIN PA4 // ?? Power loss / nAC_FAULT +#define LED_PIN PB14 // Alive +#define PS_ON_PIN PE0 +#define KILL_PIN PD5 +#define POWER_LOSS_PIN PA4 // ?? Power loss / nAC_FAULT #if ENABLED(SDSUPPORT) - #define SD_DETECT_PIN PB7 - #define SS_PIN PB_15 // USD_CS -> CS for onboard SD + #define SD_DETECT_PIN PB7 + #define SS_PIN PB_15 // USD_CS -> CS for onboard SD #endif // @@ -166,29 +166,29 @@ // #if HAS_SPI_LCD #if ENABLED(SDSUPPORT) - #define SDSS PB6 // CS for SD card in LCD + #define SDSS PB6 // CS for SD card in LCD #endif - #define BEEPER_PIN PC9 - #define LCD_PINS_RS PC12 - #define LCD_PINS_ENABLE PD7 - #define LCD_PINS_D4 PD1 - #define LCD_PINS_D5 PD2 - #define LCD_PINS_D6 PD3 - #define LCD_PINS_D7 PD4 - #define BTN_EN1 PD6 - #define BTN_EN2 PD0 - #define BTN_ENC PB12 + #define BEEPER_PIN PC9 + #define LCD_PINS_RS PC12 + #define LCD_PINS_ENABLE PD7 + #define LCD_PINS_D4 PD1 + #define LCD_PINS_D5 PD2 + #define LCD_PINS_D6 PD3 + #define LCD_PINS_D7 PD4 + #define BTN_EN1 PD6 + #define BTN_EN2 PD0 + #define BTN_ENC PB12 #endif // // ST7920 Delays // #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(96) + #define ST7920_DELAY_1 DELAY_NS(96) #endif #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(48) + #define ST7920_DELAY_2 DELAY_NS(48) #endif #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(715) + #define ST7920_DELAY_3 DELAY_NS(715) #endif diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index 45a1f68e5a..736445cdab 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -28,7 +28,7 @@ #define BOARD_INFO_NAME "RemRam v1" #define DEFAULT_MACHINE_NAME "RemRam" -#define SRAM_EEPROM_EMULATION // Emulate the EEPROM using Backup SRAM +#define SRAM_EEPROM_EMULATION // Emulate the EEPROM using Backup SRAM #if HOTENDS > 1 || E_STEPPERS > 1 #error "RemRam supports only one hotend / E-stepper." @@ -38,96 +38,96 @@ // Limit Switches // #if DISABLED(SENSORLESS_HOMING) - #define X_MIN_PIN 58 - #define X_MAX_PIN 59 - #define Y_MIN_PIN 60 - #define Y_MAX_PIN 61 - #define Z_MIN_PIN 62 - #define Z_MAX_PIN 63 + #define X_MIN_PIN 58 + #define X_MAX_PIN 59 + #define Y_MIN_PIN 60 + #define Y_MAX_PIN 61 + #define Z_MIN_PIN 62 + #define Z_MAX_PIN 63 #else - #define X_STOP_PIN 36 - #define Y_STOP_PIN 39 - #define Z_MIN_PIN 62 - #define Z_MAX_PIN 42 + #define X_STOP_PIN 36 + #define Y_STOP_PIN 39 + #define Z_MIN_PIN 62 + #define Z_MAX_PIN 42 #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 26 // EXT_D1 + #define Z_MIN_PROBE_PIN 26 // EXT_D1 #endif // // Steppers // -#define X_STEP_PIN 22 -#define X_DIR_PIN 35 -#define X_ENABLE_PIN 34 -#define X_CS_PIN 14 +#define X_STEP_PIN 22 +#define X_DIR_PIN 35 +#define X_ENABLE_PIN 34 +#define X_CS_PIN 14 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 38 -#define Y_ENABLE_PIN 37 -#define Y_CS_PIN 15 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 38 +#define Y_ENABLE_PIN 37 +#define Y_CS_PIN 15 -#define Z_STEP_PIN 24 -#define Z_DIR_PIN 41 -#define Z_ENABLE_PIN 40 -#define Z_CS_PIN 16 +#define Z_STEP_PIN 24 +#define Z_DIR_PIN 41 +#define Z_ENABLE_PIN 40 +#define Z_CS_PIN 16 -#define E0_STEP_PIN 25 -#define E0_DIR_PIN 44 -#define E0_ENABLE_PIN 43 -#define E0_CS_PIN 10 +#define E0_STEP_PIN 25 +#define E0_DIR_PIN 44 +#define E0_ENABLE_PIN 43 +#define E0_CS_PIN 10 // // Temperature Sensors // -#define TEMP_0_PIN 64 // THERM_1 -#define TEMP_1_PIN 65 // THERM_2 -#define TEMP_BED_PIN 66 // THERM_3 +#define TEMP_0_PIN 64 // THERM_1 +#define TEMP_1_PIN 65 // THERM_2 +#define TEMP_BED_PIN 66 // THERM_3 // // Heaters / Fans // -#define HEATER_0_PIN 33 -#define HEATER_BED_PIN 31 +#define HEATER_0_PIN 33 +#define HEATER_BED_PIN 31 #ifndef FAN_PIN - #define FAN_PIN 30 // "FAN1" + #define FAN_PIN 30 // "FAN1" #endif -#define FAN1_PIN 32 // "FAN2" +#define FAN1_PIN 32 // "FAN2" -#define ORIG_E0_AUTO_FAN_PIN 32 // Use this by NOT overriding E0_AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN 32 // Use this by NOT overriding E0_AUTO_FAN_PIN // // Servos // -#define SERVO0_PIN 26 // PWM_EXT1 -#define SERVO1_PIN 27 // PWM_EXT2 +#define SERVO0_PIN 26 // PWM_EXT1 +#define SERVO1_PIN 27 // PWM_EXT2 -#define SDSS 57 // Onboard SD card reader -//#define SDSS 9 // LCD SD card reader -#define LED_PIN 21 // STATUS_LED +#define SDSS 57 // Onboard SD card reader +//#define SDSS 9 // LCD SD card reader +#define LED_PIN 21 // STATUS_LED // // LCD / Controller // -#define SD_DETECT_PIN 56 // SD_CARD_DET -#define BEEPER_PIN 46 // LCD_BEEPER -#define LCD_PINS_RS 49 // LCD_RS -#define LCD_PINS_ENABLE 48 // LCD_EN -#define LCD_PINS_D4 50 // LCD_D4 -#define LCD_PINS_D5 51 // LCD_D5 -#define LCD_PINS_D6 52 // LCD_D6 -#define LCD_PINS_D7 53 // LCD_D7 -#define BTN_EN1 54 // BTN_EN1 -#define BTN_EN2 55 // BTN_EN2 -#define BTN_ENC 47 // BTN_ENC +#define SD_DETECT_PIN 56 // SD_CARD_DET +#define BEEPER_PIN 46 // LCD_BEEPER +#define LCD_PINS_RS 49 // LCD_RS +#define LCD_PINS_ENABLE 48 // LCD_EN +#define LCD_PINS_D4 50 // LCD_D4 +#define LCD_PINS_D5 51 // LCD_D5 +#define LCD_PINS_D6 52 // LCD_D6 +#define LCD_PINS_D7 53 // LCD_D7 +#define BTN_EN1 54 // BTN_EN1 +#define BTN_EN2 55 // BTN_EN2 +#define BTN_ENC 47 // BTN_ENC // // Timers // -#define STEP_TIMER 2 +#define STEP_TIMER 2 diff --git a/Marlin/src/pins/stm32f7/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h index bfc9507c45..9968d9d1f1 100644 --- a/Marlin/src/pins/stm32f7/pins_THE_BORG.h +++ b/Marlin/src/pins/stm32f7/pins_THE_BORG.h @@ -31,7 +31,7 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #ifndef E2END - #define E2END 0xFFF // EEPROM end address + #define E2END 0xFFF // EEPROM end address #endif // Ignore temp readings during development. @@ -40,148 +40,142 @@ // // Limit Switches // -#define X_MIN_PIN PE9 -#define X_MAX_PIN PE10 -#define Y_MIN_PIN PE7 -#define Y_MAX_PIN PE8 -#define Z_MIN_PIN PF15 -#define Z_MAX_PIN PG0 -#define E_MIN_PIN PE2 -#define E_MAX_PIN PE3 +#define X_MIN_PIN PE9 +#define X_MAX_PIN PE10 +#define Y_MIN_PIN PE7 +#define Y_MAX_PIN PE8 +#define Z_MIN_PIN PF15 +#define Z_MAX_PIN PG0 +#define E_MIN_PIN PE2 +#define E_MAX_PIN PE3 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PA4 + #define Z_MIN_PROBE_PIN PA4 #endif // // Steppers // -#define STEPPER_ENABLE_PIN PE0 +#define STEPPER_ENABLE_PIN PE0 -#define X_STEP_PIN PC6 // 96, 39 in Arduino -#define X_DIR_PIN PC7 -#define X_ENABLE_PIN PC8 +#define X_STEP_PIN PC6 // 96, 39 in Arduino +#define X_DIR_PIN PC7 +#define X_ENABLE_PIN PC8 +#define Y_STEP_PIN PD9 +#define Y_DIR_PIN PD10 +#define Y_ENABLE_PIN PD11 -#define Y_STEP_PIN PD9 -#define Y_DIR_PIN PD10 -#define Y_ENABLE_PIN PD11 +#define Z_STEP_PIN PE15 +#define Z_DIR_PIN PG1 +#define Z_ENABLE_PIN PD8 -#define Z_STEP_PIN PE15 -#define Z_DIR_PIN PG1 -#define Z_ENABLE_PIN PD8 +#define E0_STEP_PIN PB1 +#define E0_DIR_PIN PB2 +#define E0_ENABLE_PIN PE11 +#define E1_STEP_PIN PC4 +#define E1_DIR_PIN PC5 +#define E1_ENABLE_PIN PB0 -#define E0_STEP_PIN PB1 -#define E0_DIR_PIN PB2 -#define E0_ENABLE_PIN PE11 +#define E2_STEP_PIN PC13 +#define E2_DIR_PIN PC14 +#define E2_ENABLE_PIN PC15 +#define Z2_STEP_PIN PC13 +#define Z2_DIR_PIN PC14 +#define Z2_ENABLE_PIN PC15 -#define E1_STEP_PIN PC4 -#define E1_DIR_PIN PC5 -#define E1_ENABLE_PIN PB0 +#define SCK_PIN PA5 +#define MISO_PIN PA6 +#define MOSI_PIN PA7 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 -#define E2_STEP_PIN PC13 -#define E2_DIR_PIN PC14 -#define E2_ENABLE_PIN PC15 - -#define Z2_STEP_PIN PC13 -#define Z2_DIR_PIN PC14 -#define Z2_ENABLE_PIN PC15 - - -#define SCK_PIN PA5 -#define MISO_PIN PA6 -#define MOSI_PIN PA7 - -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define SPI6_SCK_PIN PG13 -#define SPI6_MISO_PIN PG12 -#define SPI6_MOSI_PIN PG14 +#define SPI6_SCK_PIN PG13 +#define SPI6_MISO_PIN PG12 +#define SPI6_MOSI_PIN PG14 // // Temperature Sensors // -#define TEMP_0_PIN PC3 // Analog Input -#define TEMP_1_PIN PC2 // Analog Input -#define TEMP_2_PIN PC1 // Analog Input -#define TEMP_3_PIN PC0 // Analog Input +#define TEMP_0_PIN PC3 // Analog Input +#define TEMP_1_PIN PC2 // Analog Input +#define TEMP_2_PIN PC1 // Analog Input +#define TEMP_3_PIN PC0 // Analog Input -#define TEMP_BED_PIN PF10 // Analog Input +#define TEMP_BED_PIN PF10 // Analog Input -#define TEMP_5_PIN PE12 // Analog Input, Probe temp +#define TEMP_5_PIN PE12 // Analog Input, Probe temp // // Heaters / Fans // -#define HEATER_0_PIN PD15 -#define HEATER_1_PIN PD14 -#define HEATER_BED_PIN PF6 +#define HEATER_0_PIN PD15 +#define HEATER_1_PIN PD14 +#define HEATER_BED_PIN PF6 #ifndef FAN_PIN - #define FAN_PIN PD13 + #define FAN_PIN PD13 #endif -#define FAN1_PIN PA0 -#define FAN2_PIN PA1 +#define FAN1_PIN PA0 +#define FAN2_PIN PA1 -#define ORIG_E0_AUTO_FAN_PIN PA1 // Use this by NOT overriding E0_AUTO_FAN_PIN +#define ORIG_E0_AUTO_FAN_PIN PA1 // Use this by NOT overriding E0_AUTO_FAN_PIN // // Misc. Functions // -//#define CASE_LIGHT_PIN_CI PF13 -//#define CASE_LIGHT_PIN_DO PF14 -//#define NEOPIXEL_PIN PF13 +//#define CASE_LIGHT_PIN_CI PF13 +//#define CASE_LIGHT_PIN_DO PF14 +//#define NEOPIXEL_PIN PF13 // // Průša i3 MK2 Multi Material Multiplexer Support // -#define E_MUX0_PIN PG3 -#define E_MUX1_PIN PG4 +#define E_MUX0_PIN PG3 +#define E_MUX1_PIN PG4 // // Servos // -#define SERVO0_PIN PE13 -#define SERVO1_PIN PE14 +#define SERVO0_PIN PE13 +#define SERVO1_PIN PE14 - -#define SDSS PA8 -#define SS_PIN PA8 -#define LED_PIN PA2 // Alive -#define PS_ON_PIN PA3 -#define KILL_PIN -1 //PD5 // EXP2-10 -#define PWR_LOSS PG5 // Power loss / nAC_FAULT +#define SDSS PA8 +#define SS_PIN PA8 +#define LED_PIN PA2 // Alive +#define PS_ON_PIN PA3 +#define KILL_PIN -1 //PD5 // EXP2-10 +#define PWR_LOSS PG5 // Power loss / nAC_FAULT // // MAX7219_DEBUG // -#define MAX7219_CLK_PIN PG10 // EXP1-1 -#define MAX7219_DIN_PIN PD7 // EXP1-3 -#define MAX7219_LOAD_PIN PD1 // EXP1-5 +#define MAX7219_CLK_PIN PG10 // EXP1-1 +#define MAX7219_DIN_PIN PD7 // EXP1-3 +#define MAX7219_LOAD_PIN PD1 // EXP1-5 // // LCD / Controller // -//#define SD_DETECT_PIN -1 //PB6) // EXP2-4 -#define BEEPER_PIN PG10 // EXP1-1 -#define LCD_PINS_RS PG9 // EXP1-4 -#define LCD_PINS_ENABLE PD7 // EXP1-3 -#define LCD_PINS_D4 PD1 // EXP1-5 -#define LCD_PINS_D5 PF0 // EXP1-6 -#define LCD_PINS_D6 PD3 // EXP1-7 -#define LCD_PINS_D7 PD4 // EXP1-8 -#define BTN_EN1 PD6 // EXP2-5 -#define BTN_EN2 PD0 // EXP2-3 -#define BTN_ENC PG11 // EXP1-2 +//#define SD_DETECT_PIN -1 //PB6) // EXP2-4 +#define BEEPER_PIN PG10 // EXP1-1 +#define LCD_PINS_RS PG9 // EXP1-4 +#define LCD_PINS_ENABLE PD7 // EXP1-3 +#define LCD_PINS_D4 PD1 // EXP1-5 +#define LCD_PINS_D5 PF0 // EXP1-6 +#define LCD_PINS_D6 PD3 // EXP1-7 +#define LCD_PINS_D7 PD4 // EXP1-8 +#define BTN_EN1 PD6 // EXP2-5 +#define BTN_EN2 PD0 // EXP2-3 +#define BTN_ENC PG11 // EXP1-2 diff --git a/Marlin/src/pins/teensy2/pins_5DPRINT.h b/Marlin/src/pins/teensy2/pins_5DPRINT.h index 206e22bb9c..4ee74660ea 100644 --- a/Marlin/src/pins/teensy2/pins_5DPRINT.h +++ b/Marlin/src/pins/teensy2/pins_5DPRINT.h @@ -78,71 +78,71 @@ // // Servos // -#define SERVO0_PIN 41 -#define SERVO1_PIN 42 -#define SERVO2_PIN 43 -#define SERVO3_PIN 44 +#define SERVO0_PIN 41 +#define SERVO1_PIN 42 +#define SERVO2_PIN 43 +#define SERVO3_PIN 44 // // Limit Switches // -#define X_STOP_PIN 37 // E5 -#define Y_STOP_PIN 36 // E4 -#define Z_STOP_PIN 19 // E7 +#define X_STOP_PIN 37 // E5 +#define Y_STOP_PIN 36 // E4 +#define Z_STOP_PIN 19 // E7 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 17 // C7 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 17 // C7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 13 // C3 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 13 // C3 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 12 // C2 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 12 // C2 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 11 // C1 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 11 // C1 // // Digital Microstepping // -#define X_MS1_PIN 25 // B5 -#define X_MS2_PIN 26 // B6 -#define Y_MS1_PIN 9 // E1 -#define Y_MS2_PIN 8 // E0 -#define Z_MS1_PIN 7 // D7 -#define Z_MS2_PIN 6 // D6 -#define E0_MS1_PIN 5 // D5 -#define E0_MS2_PIN 4 // D4 +#define X_MS1_PIN 25 // B5 +#define X_MS2_PIN 26 // B6 +#define Y_MS1_PIN 9 // E1 +#define Y_MS2_PIN 8 // E0 +#define Z_MS1_PIN 7 // D7 +#define Z_MS2_PIN 6 // D6 +#define E0_MS1_PIN 5 // D5 +#define E0_MS2_PIN 4 // D4 // // Temperature Sensors // -#define TEMP_0_PIN 1 // F1 Analog Input -#define TEMP_BED_PIN 0 // F0 Analog Input +#define TEMP_0_PIN 1 // F1 Analog Input +#define TEMP_BED_PIN 0 // F0 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 -#define HEATER_BED_PIN 14 // C4 +#define HEATER_0_PIN 15 // C5 +#define HEATER_BED_PIN 14 // C4 #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN 16 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 +#define SDSS 20 // B0 //DIGIPOTS slave addresses #ifndef DIGIPOT_I2C_ADDRESS_A - #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for DIGIPOT 0x2C (0x58 <- 0x2C << 1) + #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for DIGIPOT 0x2C (0x58 <- 0x2C << 1) #endif diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h index 22ceb97540..f7597dbbae 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h @@ -77,50 +77,50 @@ // // Limit Switches // -#define X_STOP_PIN 35 // A7 -#define Y_STOP_PIN 34 // A6 -#define Z_STOP_PIN 33 // A5 +#define X_STOP_PIN 35 // A7 +#define Y_STOP_PIN 34 // A6 +#define Z_STOP_PIN 33 // A5 // // Steppers // -#define X_STEP_PIN 3 // D3 -#define X_DIR_PIN 5 // D5 -#define X_ENABLE_PIN 4 // D4 -#define X_ATT_PIN 2 // D2 +#define X_STEP_PIN 3 // D3 +#define X_DIR_PIN 5 // D5 +#define X_ENABLE_PIN 4 // D4 +#define X_ATT_PIN 2 // D2 -#define Y_STEP_PIN 7 // D7 -#define Y_DIR_PIN 9 // E1 -#define Y_ENABLE_PIN 8 // E0 -#define Y_ATT_PIN 6 // D6 +#define Y_STEP_PIN 7 // D7 +#define Y_DIR_PIN 9 // E1 +#define Y_ENABLE_PIN 8 // E0 +#define Y_ATT_PIN 6 // D6 -#define Z_STEP_PIN 11 // C1 -#define Z_DIR_PIN 13 // C3 -#define Z_ENABLE_PIN 12 // C2 -#define Z_ATT_PIN 10 // C0 +#define Z_STEP_PIN 11 // C1 +#define Z_DIR_PIN 13 // C3 +#define Z_ENABLE_PIN 12 // C2 +#define Z_ATT_PIN 10 // C0 -#define E0_STEP_PIN 15 // C5 -#define E0_DIR_PIN 17 // C7 -#define E0_ENABLE_PIN 16 // C6 -#define E0_ATT_PIN 14 // C4 +#define E0_STEP_PIN 15 // C5 +#define E0_DIR_PIN 17 // C7 +#define E0_ENABLE_PIN 16 // C6 +#define E0_ATT_PIN 14 // C4 // // Temperature Sensors // -#define TEMP_0_PIN 7 // F7 Analog Input -#define TEMP_BED_PIN 6 // F6 Analog Input +#define TEMP_0_PIN 7 // F7 Analog Input +#define TEMP_BED_PIN 6 // F6 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 32 // A4 Extruder -#define HEATER_BED_PIN 18 // E6 Bed +#define HEATER_0_PIN 32 // A4 Extruder +#define HEATER_BED_PIN 18 // E6 Bed #ifndef FAN_PIN - #define FAN_PIN 31 // A3 Fan + #define FAN_PIN 31 // A3 Fan #endif // // Misc. Functions // -#define LED_PIN 19 // E7 +#define LED_PIN 19 // E7 diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h index 88b045b833..575428f097 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h @@ -84,55 +84,55 @@ // // Limit Switches // -#define X_STOP_PIN 45 // F7 -#define Y_STOP_PIN 12 // C2 -#define Z_STOP_PIN 36 // E4 +#define X_STOP_PIN 45 // F7 +#define Y_STOP_PIN 12 // C2 +#define Z_STOP_PIN 36 // E4 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 11 // C1 + #define Z_MIN_PROBE_PIN 11 // C1 #endif // // Steppers // -#define X_STEP_PIN 9 // E1 -#define X_DIR_PIN 8 // E0 -#define X_ENABLE_PIN 23 // B3 +#define X_STEP_PIN 9 // E1 +#define X_DIR_PIN 8 // E0 +#define X_ENABLE_PIN 23 // B3 -#define Y_STEP_PIN 7 // D7 -#define Y_DIR_PIN 6 // D6 -#define Y_ENABLE_PIN 20 // B0 +#define Y_STEP_PIN 7 // D7 +#define Y_DIR_PIN 6 // D6 +#define Y_ENABLE_PIN 20 // B0 -#define Z_STEP_PIN 5 // D5 -#define Z_DIR_PIN 4 // D4 -#define Z_ENABLE_PIN 37 // E5 +#define Z_STEP_PIN 5 // D5 +#define Z_DIR_PIN 4 // D4 +#define Z_ENABLE_PIN 37 // E5 -#define E0_STEP_PIN 47 // E3 -#define E0_DIR_PIN 46 // E2 -#define E0_ENABLE_PIN 25 // B5 +#define E0_STEP_PIN 47 // E3 +#define E0_DIR_PIN 46 // E2 +#define E0_ENABLE_PIN 25 // B5 // // Temperature Sensors // -#define TEMP_0_PIN 2 // F2 Analog Input -#define TEMP_1_PIN 1 // F1 Analog Input -#define TEMP_BED_PIN 0 // F0 Analog Input +#define TEMP_0_PIN 2 // F2 Analog Input +#define TEMP_1_PIN 1 // F1 Analog Input +#define TEMP_BED_PIN 0 // F0 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 27 // B7 -#define HEATER_BED_PIN 26 // B6 Bed +#define HEATER_0_PIN 27 // B7 +#define HEATER_BED_PIN 26 // B6 Bed #ifndef FAN_PIN - #define FAN_PIN 16 // C6 Fan, PWM3A + #define FAN_PIN 16 // C6 Fan, PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 -#define SD_DETECT_PIN 24 // B4 -#define LED_PIN 13 // C3 +#define SDSS 20 // B0 +#define SD_DETECT_PIN 24 // B4 +#define LED_PIN 13 // C3 diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 4f10e08084..68c548f833 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -74,95 +74,95 @@ // // Limit Switches // -#define X_STOP_PIN 47 // E3 -#define Y_STOP_PIN 20 // B0 SS -#define Z_STOP_PIN 36 // E4 +#define X_STOP_PIN 47 // E3 +#define Y_STOP_PIN 20 // B0 SS +#define Z_STOP_PIN 36 // E4 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_1_PIN 44 // F6 -#define HEATER_2_PIN 45 // F7 -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_1_PIN 44 // F6 +#define HEATER_2_PIN 45 // F7 +#define HEATER_BED_PIN 14 // C4 PWM3C #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN 16 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 26 // B6 SDCS -#define FILWIDTH_PIN 2 // Analog Input +#define SDSS 26 // B6 SDCS +#define FILWIDTH_PIN 2 // Analog Input // // LCD / Controller // #if BOTH(ULTRA_LCD, NEWPANEL) - #define LCD_PINS_RS 9 // E1 JP11-11 - #define LCD_PINS_ENABLE 8 // E0 JP11-10 - #define LCD_PINS_D4 7 // D7 JP11-8 - #define LCD_PINS_D5 6 // D6 JP11-7 - #define LCD_PINS_D6 5 // D5 JP11-6 - #define LCD_PINS_D7 4 // D4 JP11-5 + #define LCD_PINS_RS 9 // E1 JP11-11 + #define LCD_PINS_ENABLE 8 // E0 JP11-10 + #define LCD_PINS_D4 7 // D7 JP11-8 + #define LCD_PINS_D5 6 // D6 JP11-7 + #define LCD_PINS_D6 5 // D5 JP11-6 + #define LCD_PINS_D7 4 // D4 JP11-5 #if ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 8 // E0 JP11-10 + #define BEEPER_PIN 8 // E0 JP11-10 - #define DOGLCD_A0 40 // F2 JP2-2 - #define DOGLCD_CS 41 // F3 JP2-4 + #define DOGLCD_A0 40 // F2 JP2-2 + #define DOGLCD_CS 41 // F3 JP2-4 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 2 // D2 TX1 JP2-5 - #define BTN_EN2 3 // D3 RX1 JP2-7 - #define BTN_ENC 45 // F7 TDI JP2-12 + #define BTN_EN1 2 // D2 TX1 JP2-5 + #define BTN_EN2 3 // D3 RX1 JP2-7 + #define BTN_ENC 45 // F7 TDI JP2-12 #undef SDSS - #define SDSS 43 // F5 TMS JP2-8 + #define SDSS 43 // F5 TMS JP2-8 - #define STAT_LED_RED_PIN 12 // C2 JP11-14 - #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 + #define STAT_LED_RED_PIN 12 // C2 JP11-14 + #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 3 // D3 RX1 JP2-7 - #define BTN_EN2 2 // D2 TX1 JP2-5 - #define BTN_ENC 41 // F3 JP2-4 + #define BTN_EN1 3 // D3 RX1 JP2-7 + #define BTN_EN2 2 // D2 TX1 JP2-5 + #define BTN_ENC 41 // F3 JP2-4 #undef SDSS - #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 + #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 #else - #define BTN_EN1 10 // C0 JP11-12 - #define BTN_EN2 11 // C1 JP11-13 - #define BTN_ENC 12 // C2 JP11-14 + #define BTN_EN1 10 // C0 JP11-12 + #define BTN_EN2 11 // C1 JP11-13 + #define BTN_ENC 12 // C2 JP11-14 #endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index c1198a4d4b..f5f05ddeaf 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -99,46 +99,46 @@ // // Limit Switches // -#define X_STOP_PIN 47 // E3 -#define Y_STOP_PIN 24 // B4 PWM2A -#define Z_STOP_PIN 36 // E4 +#define X_STOP_PIN 47 // E3 +#define Y_STOP_PIN 24 // B4 PWM2A +#define Z_STOP_PIN 36 // E4 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define E1_STEP_PIN 25 // B5 - #define E1_DIR_PIN 37 // E5 - #define E1_ENABLE_PIN 42 // F4 + #define E1_STEP_PIN 25 // B5 + #define E1_DIR_PIN 37 // E5 + #define E1_ENABLE_PIN 42 // F4 - #define E2_STEP_PIN 2 // D2 - #define E2_DIR_PIN 3 // D3 - #define E2_ENABLE_PIN 43 // F5 + #define E2_STEP_PIN 2 // D2 + #define E2_DIR_PIN 3 // D3 + #define E2_ENABLE_PIN 43 // F5 #else - #define E1_STEP_PIN 2 // D2 - #define E1_DIR_PIN 3 // D3 - #define E1_ENABLE_PIN 43 // F5 + #define E1_STEP_PIN 2 // D2 + #define E1_DIR_PIN 3 // D3 + #define E1_ENABLE_PIN 43 // F5 - #define E2_STEP_PIN 25 // B5 - #define E2_DIR_PIN 37 // E5 - #define E2_ENABLE_PIN 42 // F4 + #define E2_STEP_PIN 25 // B5 + #define E2_DIR_PIN 37 // E5 + #define E2_ENABLE_PIN 42 // F4 #endif #endif // NO_EXTRUDRBOARD @@ -154,46 +154,46 @@ #define DAC_STEPPER_ORDER { 3, 2, 1, 0 } #define DAC_STEPPER_SENSE 0.11 -#define DAC_STEPPER_ADDRESS 0 -#define DAC_STEPPER_MAX 3520 -#define DAC_STEPPER_VREF 1 // internal Vref, gain 1x = 2.048V -#define DAC_STEPPER_GAIN 0 -#define DAC_OR_ADDRESS 0x00 +#define DAC_STEPPER_ADDRESS 0 +#define DAC_STEPPER_MAX 3520 +#define DAC_STEPPER_VREF 1 // internal Vref, gain 1x = 2.048V +#define DAC_STEPPER_GAIN 0 +#define DAC_OR_ADDRESS 0x00 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input (Extruder) -#define TEMP_BED_PIN 0 // Analog Input (Bed) +#define TEMP_0_PIN 1 // Analog Input (Extruder) +#define TEMP_BED_PIN 0 // Analog Input (Bed) #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define TEMP_1_PIN 2 // Analog Input (Extrudrboard A THERM) - #define TEMP_2_PIN 3 // Analog Input (Extrudrboard B THERM) + #define TEMP_1_PIN 2 // Analog Input (Extrudrboard A THERM) + #define TEMP_2_PIN 3 // Analog Input (Extrudrboard B THERM) #else - #define TEMP_1_PIN 3 // Analog Input (Extrudrboard B THERM) - #define TEMP_2_PIN 2 // Analog Input (Extrudrboard A THERM) + #define TEMP_1_PIN 3 // Analog Input (Extrudrboard B THERM) + #define TEMP_2_PIN 2 // Analog Input (Extrudrboard A THERM) #endif #endif // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define HEATER_1_PIN 44 // F6 - Extrudrboard A HOTEND - #define HEATER_2_PIN 45 // F7 - Extrudrboard B HOTEND + #define HEATER_1_PIN 44 // F6 - Extrudrboard A HOTEND + #define HEATER_2_PIN 45 // F7 - Extrudrboard B HOTEND #else - #define HEATER_1_PIN 45 // F7 - Extrudrboard B HOTEND - #define HEATER_2_PIN 44 // F6 - Extrudrboard A HOTEND + #define HEATER_1_PIN 45 // F7 - Extrudrboard B HOTEND + #define HEATER_2_PIN 44 // F6 - Extrudrboard A HOTEND #endif #endif #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN 16 // C6 PWM3A #endif // @@ -202,49 +202,49 @@ //#define USE_INTERNAL_SD #if HAS_SPI_LCD - #define LCD_PINS_RS 9 // E1 JP11-11 - #define LCD_PINS_ENABLE 8 // E0 JP11-10 - #define LCD_PINS_D4 7 // D7 JP11-8 - #define LCD_PINS_D5 6 // D6 JP11-7 - #define LCD_PINS_D6 5 // D5 JP11-6 - #define LCD_PINS_D7 4 // D4 JP11-5 + #define LCD_PINS_RS 9 // E1 JP11-11 + #define LCD_PINS_ENABLE 8 // E0 JP11-10 + #define LCD_PINS_D4 7 // D7 JP11-8 + #define LCD_PINS_D5 6 // D6 JP11-7 + #define LCD_PINS_D6 5 // D5 JP11-6 + #define LCD_PINS_D7 4 // D4 JP11-5 #if ANY(VIKI2, miniVIKI) - #define BEEPER_PIN 8 // E0 JP11-10 - #define DOGLCD_A0 40 // F2 JP2-2 - #define DOGLCD_CS 41 // F3 JP2-4 + #define BEEPER_PIN 8 // E0 JP11-10 + #define DOGLCD_A0 40 // F2 JP2-2 + #define DOGLCD_CS 41 // F3 JP2-4 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 2 // D2 TX1 JP2-5 - #define BTN_EN2 3 // D3 RX1 JP2-7 - #define BTN_ENC 45 // F7 TDI JP2-12 + #define BTN_EN1 2 // D2 TX1 JP2-5 + #define BTN_EN2 3 // D3 RX1 JP2-7 + #define BTN_ENC 45 // F7 TDI JP2-12 - #define SDSS 3 // F5 TMS JP2-8 + #define SDSS 3 // F5 TMS JP2-8 - #define STAT_LED_RED_PIN 12 // C2 JP11-14 - #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 + #define STAT_LED_RED_PIN 12 // C2 JP11-14 + #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 #elif ENABLED(MINIPANEL) #if DISABLED(USE_INTERNAL_SD) // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define SDSS 11 // 36 C1 EXP2-13 EXP2-07 - #define SD_DETECT_PIN 9 // 34 E1 EXP2-11 EXP2-04 + #define SDSS 11 // 36 C1 EXP2-13 EXP2-07 + #define SD_DETECT_PIN 9 // 34 E1 EXP2-11 EXP2-04 #endif // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define DOGLCD_A0 4 // 29 D4 EXP2-05 EXP1-04 - #define DOGLCD_CS 5 // 30 D5 EXP2-06 EXP1-05 - #define BTN_ENC 6 // 31 D6 EXP2-07 EXP1-09 - #define BEEPER_PIN 7 // 32 D7 EXP2-08 EXP1-10 - #define KILL_PIN 8 // 33 E0 EXP2-10 EXP2-03 - #define BTN_EN1 10 // 35 C0 EXP2-12 EXP2-06 - #define BTN_EN2 12 // 37 C2 EXP2-14 EXP2-08 - //#define LCD_BACKLIGHT_PIN 43 // 56 F5 EXP1-12 Not Implemented - //#define SCK 21 // 11 B1 ICSP-04 EXP2-09 - //#define MOSI 22 // 12 B2 ICSP-03 EXP2-05 - //#define MISO 23 // 13 B3 ICSP-06 EXP2-05 + #define DOGLCD_A0 4 // 29 D4 EXP2-05 EXP1-04 + #define DOGLCD_CS 5 // 30 D5 EXP2-06 EXP1-05 + #define BTN_ENC 6 // 31 D6 EXP2-07 EXP1-09 + #define BEEPER_PIN 7 // 32 D7 EXP2-08 EXP1-10 + #define KILL_PIN 8 // 33 E0 EXP2-10 EXP2-03 + #define BTN_EN1 10 // 35 C0 EXP2-12 EXP2-06 + #define BTN_EN2 12 // 37 C2 EXP2-14 EXP2-08 + //#define LCD_BACKLIGHT_PIN 43 // 56 F5 EXP1-12 Not Implemented + //#define SCK 21 // 11 B1 ICSP-04 EXP2-09 + //#define MOSI 22 // 12 B2 ICSP-03 EXP2-05 + //#define MISO 23 // 13 B3 ICSP-06 EXP2-05 // increase delays #define BOARD_ST7920_DELAY_1 DELAY_NS(313) @@ -253,9 +253,9 @@ #else - #define BTN_EN1 10 // C0 JP11-12 - #define BTN_EN2 11 // C1 JP11-13 - #define BTN_ENC 12 // C2 JP11-14 + #define BTN_EN1 10 // C0 JP11-12 + #define BTN_EN2 11 // C1 JP11-13 + #define BTN_ENC 12 // C2 JP11-14 #endif @@ -266,7 +266,7 @@ // // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. #ifndef SDSS - #define SDSS 20 // 10 B0 + #define SDSS 20 // 10 B0 #endif /** @@ -277,5 +277,5 @@ * which will let you use Channel B on the Extrudrboard as E1. */ #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 2 // Analog Input + #define FILWIDTH_PIN 2 // Analog Input #endif diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index 0ced699938..01003b056d 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -73,56 +73,56 @@ // // Servos // -#define SERVO0_PIN 39 // F1 In teensy's pin definition for pinMode (in servo.cpp) +#define SERVO0_PIN 39 // F1 In teensy's pin definition for pinMode (in servo.cpp) // // Limit Switches // -#define X_STOP_PIN 25 // B5 -#define Y_STOP_PIN 26 // B6 -//#define Z_STOP_PIN 27 // B7 -#define Z_STOP_PIN 36 // E4 For inductive sensor. -//#define E_STOP_PIN 36 // E4 +#define X_STOP_PIN 25 // B5 +#define Y_STOP_PIN 26 // B6 +//#define Z_STOP_PIN 27 // B7 +#define Z_STOP_PIN 36 // E4 For inductive sensor. +//#define E_STOP_PIN 36 // E4 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) -#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) +#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C - Bed +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C - Bed #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN 16 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 +#define SDSS 20 // B0 // Extension header pin mapping // ---------------------------- @@ -133,53 +133,53 @@ // PWM-D24 A4 (An), IO // 5V GND // 12V GND -#define EXT_AUX_SCL_D0 0 // D0 PWM0B -#define EXT_AUX_SDA_D1 1 // D1 -#define EXT_AUX_RX1_D2 2 // D2 -#define EXT_AUX_TX1_D3 3 // D3 -#define EXT_AUX_PWM_D24 24 // B4 PWM2A -#define EXT_AUX_A0 0 // F0 Analog Input -#define EXT_AUX_A0_IO 38 // F0 Digital IO -#define EXT_AUX_A1 1 // F1 Analog Input -#define EXT_AUX_A1_IO 39 // F1 Digital IO -#define EXT_AUX_A2 2 // F2 Analog Input -#define EXT_AUX_A2_IO 40 // F2 Digital IO -#define EXT_AUX_A3 3 // F3 Analog Input -#define EXT_AUX_A3_IO 41 // F3 Digital IO -#define EXT_AUX_A4 4 // F4 Analog Input -#define EXT_AUX_A4_IO 42 // F4 Digital IO +#define EXT_AUX_SCL_D0 0 // D0 PWM0B +#define EXT_AUX_SDA_D1 1 // D1 +#define EXT_AUX_RX1_D2 2 // D2 +#define EXT_AUX_TX1_D3 3 // D3 +#define EXT_AUX_PWM_D24 24 // B4 PWM2A +#define EXT_AUX_A0 0 // F0 Analog Input +#define EXT_AUX_A0_IO 38 // F0 Digital IO +#define EXT_AUX_A1 1 // F1 Analog Input +#define EXT_AUX_A1_IO 39 // F1 Digital IO +#define EXT_AUX_A2 2 // F2 Analog Input +#define EXT_AUX_A2_IO 40 // F2 Digital IO +#define EXT_AUX_A3 3 // F3 Analog Input +#define EXT_AUX_A3_IO 41 // F3 Digital IO +#define EXT_AUX_A4 4 // F4 Analog Input +#define EXT_AUX_A4_IO 42 // F4 Digital IO // // LCD / Controller // -#define BEEPER_PIN -1 -#define LCD_PINS_RS -1 -#define LCD_PINS_ENABLE -1 +#define BEEPER_PIN -1 +#define LCD_PINS_RS -1 +#define LCD_PINS_ENABLE -1 #if ENABLED(SAV_3DLCD) // For LCD SHIFT register LCD - #define SR_DATA_PIN EXT_AUX_SDA_D1 - #define SR_CLK_PIN EXT_AUX_SCL_D0 + #define SR_DATA_PIN EXT_AUX_SDA_D1 + #define SR_CLK_PIN EXT_AUX_SCL_D0 #endif #if EITHER(SAV_3DLCD, SAV_3DGLCD) - #define BTN_EN1 EXT_AUX_A1_IO - #define BTN_EN2 EXT_AUX_A0_IO - #define BTN_ENC EXT_AUX_PWM_D24 + #define BTN_EN1 EXT_AUX_A1_IO + #define BTN_EN2 EXT_AUX_A0_IO + #define BTN_ENC EXT_AUX_PWM_D24 - #define KILL_PIN EXT_AUX_A2_IO - #define HOME_PIN EXT_AUX_A4_IO + #define KILL_PIN EXT_AUX_A2_IO + #define HOME_PIN EXT_AUX_A4_IO -#else // Use the expansion header for spindle control +#else // Use the expansion header for spindle control // // M3/M4/M5 - Spindle/Laser Control // - #define SPINDLE_LASER_PWM_PIN 24 // B4 PWM2A - #define SPINDLE_LASER_ENA_PIN 39 // F1 Pin should have a pullup! - #define SPINDLE_DIR_PIN 40 // F2 + #define SPINDLE_LASER_PWM_PIN 24 // B4 PWM2A + #define SPINDLE_LASER_ENA_PIN 39 // F1 Pin should have a pullup! + #define SPINDLE_DIR_PIN 40 // F2 - #define CASE_LIGHT_PIN 0 // D0 PWM0B + #define CASE_LIGHT_PIN 0 // D0 PWM0B #endif diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index 985cd46df4..eb116ee3e8 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -116,70 +116,70 @@ // // Limit Switches // -#define X_STOP_PIN 2 // D2 -#define Y_STOP_PIN 3 // D3 -#define Z_STOP_PIN 4 // D4 +#define X_STOP_PIN 2 // D2 +#define Y_STOP_PIN 3 // D3 +#define Z_STOP_PIN 4 // D4 // // Steppers // -#define X_STEP_PIN 28 // A0 Marlin -#define X_DIR_PIN 29 // A1 Marlin -#define X_ENABLE_PIN 26 // B6 +#define X_STEP_PIN 28 // A0 Marlin +#define X_DIR_PIN 29 // A1 Marlin +#define X_ENABLE_PIN 26 // B6 -#define Y_STEP_PIN 30 // A2 Marlin -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 26 // B6 Shared w/x +#define Y_STEP_PIN 30 // A2 Marlin +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 26 // B6 Shared w/x -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 26 // B6 Shared w/x +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 26 // B6 Shared w/x -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 26 // B6 Shared w/x +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 26 // B6 Shared w/x // // Temperature Sensors // -#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) -#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) +#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN 15 // C5 PWM3B Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A Fan + #define FAN_PIN 16 // C6 PWM3A Fan #endif // // Misc. Functions // -#define SDSS 20 // B0 -#define LED_PIN 6 // D6 -#define PS_ON_PIN 27 // B7 -#define CASE_LIGHT_PIN 1 // D1 PWM2B MUST BE HARDWARE PWM +#define SDSS 20 // B0 +#define LED_PIN 6 // D6 +#define PS_ON_PIN 27 // B7 +#define CASE_LIGHT_PIN 1 // D1 PWM2B MUST BE HARDWARE PWM // // LCD / Controller // #if ENABLED(ULTIPANEL) - #define LCD_PINS_RS 8 // E0 - #define LCD_PINS_ENABLE 9 // E1 - #define LCD_PINS_D4 10 // C0 - #define LCD_PINS_D5 11 // C1 - #define LCD_PINS_D6 12 // C2 - #define LCD_PINS_D7 13 // C3 - #define BTN_EN1 38 // F0 - #define BTN_EN2 39 // F1 - #define BTN_ENC 40 // F2 + #define LCD_PINS_RS 8 // E0 + #define LCD_PINS_ENABLE 9 // E1 + #define LCD_PINS_D4 10 // C0 + #define LCD_PINS_D5 11 // C1 + #define LCD_PINS_D6 12 // C2 + #define LCD_PINS_D7 13 // C3 + #define BTN_EN1 38 // F0 + #define BTN_EN2 39 // F1 + #define BTN_ENC 40 // F2 #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // D5 Pin should have a pullup! -#define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM -#define SPINDLE_DIR_PIN 7 // D7 +#define SPINDLE_LASER_ENA_PIN 5 // D5 Pin should have a pullup! +#define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 7 // D7 diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index 72eb21c1aa..05f433cb89 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -82,82 +82,81 @@ // // Limit Switch definitions that match the SCHEMATIC // -//#define X_STOP_PIN 25 // B5 -//#define Y_STOP_PIN 26 // B6 -//#define Z_STOP_PIN 27 // B7 -//#define E_STOP_PIN 36 // E4 - +//#define X_STOP_PIN 25 // B5 +//#define Y_STOP_PIN 26 // B6 +//#define Z_STOP_PIN 27 // B7 +//#define E_STOP_PIN 36 // E4 // // Limit Switch definitions that match the SILKSCREEN // -#define X_STOP_PIN 26 // B6 -#define Y_STOP_PIN 27 // B7 -#define Z_STOP_PIN 36 // E4 -//#define E_STOP_PIN 25 // B5 +#define X_STOP_PIN 26 // B6 +#define Y_STOP_PIN 27 // B7 +#define Z_STOP_PIN 36 // E4 +//#define E_STOP_PIN 25 // B5 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (Extruder) -#define TEMP_BED_PIN 6 // Analog Input (Bed) +#define TEMP_0_PIN 7 // Analog Input (Extruder) +#define TEMP_BED_PIN 6 // Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN 16 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 JP31-6 -#define CASE_LIGHT_PIN 0 // D0 IO-14 PWM0B +#define SDSS 20 // B0 JP31-6 +#define CASE_LIGHT_PIN 0 // D0 IO-14 PWM0B // // LCD / Controller // #if BOTH(ULTRA_LCD, NEWPANEL) - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 3 // D3 IO-8 - #define BTN_EN2 2 // D2 IO-10 - #define BTN_ENC 41 // F3 IO-7 - #define SDSS 38 // F0 IO-13 use SD card on Panelolu2 + #define BTN_EN1 3 // D3 IO-8 + #define BTN_EN2 2 // D2 IO-10 + #define BTN_ENC 41 // F3 IO-7 + #define SDSS 38 // F0 IO-13 use SD card on Panelolu2 #endif - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #endif // HAS_SPI_LCD && NEWPANEL // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM -#define SPINDLE_LASER_ENA_PIN 39 // F1 IO-11 - Pin should have a pullup! -#define SPINDLE_DIR_PIN 40 // F2 IO-9 +#define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENA_PIN 39 // F1 IO-11 - Pin should have a pullup! +#define SPINDLE_DIR_PIN 40 // F2 IO-9 diff --git a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h index 6c43c4aaa8..0f895c9e6b 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h @@ -35,87 +35,87 @@ #define BOARD_INFO_NAME "Teensy3.2" #endif -#define AT90USB 1286 // Disable MarlinSerial etc. +#define AT90USB 1286 // Disable MarlinSerial etc. #define USBCON //1286 // Disable MarlinSerial etc. // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 4 -#define Z_STOP_PIN 5 +#define X_STOP_PIN 3 +#define Y_STOP_PIN 4 +#define Z_STOP_PIN 5 // // Steppers // -#define X_STEP_PIN 5 -#define X_DIR_PIN 6 -#define X_ENABLE_PIN 2 +#define X_STEP_PIN 5 +#define X_DIR_PIN 6 +#define X_ENABLE_PIN 2 -#define Y_STEP_PIN 7 -#define Y_DIR_PIN 8 -#define Y_ENABLE_PIN 2 +#define Y_STEP_PIN 7 +#define Y_DIR_PIN 8 +#define Y_ENABLE_PIN 2 -#define Z_STEP_PIN 9 -#define Z_DIR_PIN 10 -#define Z_ENABLE_PIN 2 +#define Z_STEP_PIN 9 +#define Z_DIR_PIN 10 +#define Z_ENABLE_PIN 2 -#define E0_STEP_PIN 11 -#define E0_DIR_PIN 12 -#define E0_ENABLE_PIN 2 +#define E0_STEP_PIN 11 +#define E0_DIR_PIN 12 +#define E0_ENABLE_PIN 2 -//#define E1_STEP_PIN 33 -//#define E1_DIR_PIN 34 -//#define E1_ENABLE_PIN 35 +//#define E1_STEP_PIN 33 +//#define E1_DIR_PIN 34 +//#define E1_ENABLE_PIN 35 // // Heaters / Fans // -#define HEATER_0_PIN 20 +#define HEATER_0_PIN 20 // #define HEATER_1_PIN 36 -#define HEATER_BED_PIN 21 +#define HEATER_BED_PIN 21 #ifndef FAN_PIN - #define FAN_PIN 22 + #define FAN_PIN 22 #endif // // Temperature Sensors // -#define TEMP_0_PIN 14 // Analog Input - Extruder 2 => A2 -//#define TEMP_1_PIN 0 // Analog Input -#define TEMP_BED_PIN 15 // Analog Input - Bed +#define TEMP_0_PIN 14 // Analog Input - Extruder 2 => A2 +//#define TEMP_1_PIN 0 // Analog Input +#define TEMP_BED_PIN 15 // Analog Input - Bed #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 6 // Analog Input + #define FILWIDTH_PIN 6 // Analog Input #endif // // Misc. Functions // -//#define SDSS 16 // 8 -#define LED_PIN 13 +//#define SDSS 16 // 8 +#define LED_PIN 13 -//#define SOL1_PIN 28 +//#define SOL1_PIN 28 // // LCD / Controller // -//#define SCK_PIN 13 -//#define MISO_PIN 12 -//#define MOSI_PIN 11 +//#define SCK_PIN 13 +//#define MISO_PIN 12 +//#define MOSI_PIN 11 /* #if HAS_SPI_LCD - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 41 - #define LCD_PINS_D4 42 - #define LCD_PINS_D5 43 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 45 - #define BTN_EN1 46 - #define BTN_EN2 47 - #define BTN_ENC 48 + #define LCD_PINS_RS 40 + #define LCD_PINS_ENABLE 41 + #define LCD_PINS_D4 42 + #define LCD_PINS_D5 43 + #define LCD_PINS_D6 44 + #define LCD_PINS_D7 45 + #define BTN_EN1 46 + #define BTN_EN2 47 + #define BTN_ENC 48 #endif */ diff --git a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h index 28fd51b8a0..8528533d7b 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h @@ -37,7 +37,7 @@ #define BOARD_INFO_NAME "Teensy3.6" #endif -#define AT90USB 1286 // Disable MarlinSerial etc. +#define AT90USB 1286 // Disable MarlinSerial etc. #define USBCON //1286 // Disable MarlinSerial etc. /* @@ -83,80 +83,80 @@ D8 HEATER_BED_PIN CS1 RX4 A12 31 | 46 * * 47 | 34 A15 PWM // // Limit Switches // -#define X_STOP_PIN 24 -#define Y_STOP_PIN 26 -#define Z_STOP_PIN 28 +#define X_STOP_PIN 24 +#define Y_STOP_PIN 26 +#define Z_STOP_PIN 28 // // Steppers // -#define X_STEP_PIN 22 -#define X_DIR_PIN 21 -#define X_ENABLE_PIN 39 +#define X_STEP_PIN 22 +#define X_DIR_PIN 21 +#define X_ENABLE_PIN 39 -#define Y_STEP_PIN 19 -#define Y_DIR_PIN 18 -#define Y_ENABLE_PIN 20 +#define Y_STEP_PIN 19 +#define Y_DIR_PIN 18 +#define Y_ENABLE_PIN 20 -#define Z_STEP_PIN 38 -#define Z_DIR_PIN 37 -#define Z_ENABLE_PIN 17 +#define Z_STEP_PIN 38 +#define Z_DIR_PIN 37 +#define Z_ENABLE_PIN 17 -#define E0_STEP_PIN 31 -#define E0_DIR_PIN 30 -#define E0_ENABLE_PIN 32 +#define E0_STEP_PIN 31 +#define E0_DIR_PIN 30 +#define E0_ENABLE_PIN 32 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 35 +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 35 -#define HEATER_0_PIN 30 -#define HEATER_1_PIN 36 -#define HEATER_BED_PIN 31 +#define HEATER_0_PIN 30 +#define HEATER_1_PIN 36 +#define HEATER_BED_PIN 31 #ifndef FAN_PIN - #define FAN_PIN 2 + #define FAN_PIN 2 #endif -#define TEMP_0_PIN 2 // Extruder / Analog pin numbering: 2 => A2 -#define TEMP_1_PIN 0 -#define TEMP_BED_PIN 1 // Bed / Analog pin numbering +#define TEMP_0_PIN 2 // Extruder / Analog pin numbering: 2 => A2 +#define TEMP_1_PIN 0 +#define TEMP_BED_PIN 1 // Bed / Analog pin numbering -#define SDSS 39 // 8 -#define LED_PIN 13 -#define PS_ON_PIN 1 -#define ALARM_PIN -1 +#define SDSS 39 // 8 +#define LED_PIN 13 +#define PS_ON_PIN 1 +#define ALARM_PIN -1 -#define FILWIDTH_PIN 6 -#define SOL1_PIN 28 +#define FILWIDTH_PIN 6 +#define SOL1_PIN 28 #if 0 // Pretty sure this is obsolete! // Please use Marlin 1.1.x pins files as reference for new pins files. #ifndef SDSUPPORT // these are defined in the SD library if building with SD support - #define SCK_PIN 13 - #define MISO_PIN 12 - #define MOSI_PIN 11 + #define SCK_PIN 13 + #define MISO_PIN 12 + #define MOSI_PIN 11 #endif #endif #if HAS_SPI_LCD - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 41 - #define LCD_PINS_D4 42 - #define LCD_PINS_D5 43 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 45 + #define LCD_PINS_RS 40 + #define LCD_PINS_ENABLE 41 + #define LCD_PINS_D4 42 + #define LCD_PINS_D5 43 + #define LCD_PINS_D6 44 + #define LCD_PINS_D7 45 #endif #if ENABLED(NEWPANEL) - #define BTN_EN1 46 - #define BTN_EN2 47 - #define BTN_ENC 48 + #define BTN_EN1 46 + #define BTN_EN2 47 + #define BTN_ENC 48 #endif #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 #endif From 2460a3dfbb3e75fe273f15bd07ded1757dff1b2a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 23:31:02 -0500 Subject: [PATCH 0023/1454] Fix custom version file include --- Marlin/src/core/macros.h | 4 ++++ Marlin/src/inc/MarlinConfigPre.h | 8 ++------ 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 56ec11bd7c..bcee642368 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -21,6 +21,10 @@ */ #pragma once +#if !defined(__has_include) + #define __has_include(...) 1 +#endif + #define ABCE 4 #define XYZE 4 #define ABC 3 diff --git a/Marlin/src/inc/MarlinConfigPre.h b/Marlin/src/inc/MarlinConfigPre.h index 1385f9e19f..d84f751200 100644 --- a/Marlin/src/inc/MarlinConfigPre.h +++ b/Marlin/src/inc/MarlinConfigPre.h @@ -37,12 +37,8 @@ #include "../../Configuration.h" #ifdef CUSTOM_VERSION_FILE - #if defined(__has_include) - #if __has_include(XSTR(../../CUSTOM_VERSION_FILE)) - #include XSTR(../../CUSTOM_VERSION_FILE) - #endif - #else - #include XSTR(../../CUSTOM_VERSION_FILE) + #if __has_include(STRINGIFY(../../CUSTOM_VERSION_FILE)) + #include STRINGIFY(../../CUSTOM_VERSION_FILE) #endif #endif From e7a9f173718198b6196de0ee7f1b9d4aab84ecd2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Mar 2020 23:38:44 -0500 Subject: [PATCH 0024/1454] Tweak serial port descriptions --- Marlin/Configuration.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 007b8fc5df..df99f8b676 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -99,6 +99,7 @@ /** * Select the serial port on the board to use for communication with the host. * This allows the connection of wireless adapters (for instance) to non-default port pins. + * Serial port -1 is the USB emulated serial port, if available. * Note: The first serial port (-1 or 0) will always be used by the Arduino bootloader. * * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] @@ -107,9 +108,6 @@ /** * Select a secondary serial port on the board to use for communication with the host. - * This allows the connection of wireless adapters (for instance) to non-default port pins. - * Serial port -1 is the USB emulated serial port, if available. - * * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] */ //#define SERIAL_PORT_2 -1 From 27c281eec3729e819d1329d8eae4450a4cbf2d38 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 23 Mar 2020 00:03:08 +0000 Subject: [PATCH 0025/1454] [cron] Bump distribution date (2020-03-23) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2f99b9a6ed..22d2ac724c 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-22" + #define STRING_DISTRIBUTION_DATE "2020-03-23" #endif /** From 717c2168519001a2f5196282a75eb6cf0eb704fd Mon Sep 17 00:00:00 2001 From: RasmusAaen Date: Mon, 23 Mar 2020 23:34:38 +0100 Subject: [PATCH 0026/1454] Fix Copymaster Y_MAX pin (#17267) --- Marlin/src/pins/ramps/pins_COPYMASTER_3D.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h index 7ee66b1194..8f61ef47dc 100644 --- a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h +++ b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h @@ -24,6 +24,7 @@ #define BOARD_INFO_NAME "Copymaster 3D RAMPS" #define Z_STEP_PIN 47 +#define Y_MAX_PIN 14 #define FIL_RUNOUT_PIN 15 #define SD_DETECT_PIN 66 From fe154fa5dee7c2c3a796c9fd634fd422ee944103 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 22 Mar 2020 00:00:19 -0500 Subject: [PATCH 0027/1454] Fix CONTROLLER_FAN options compile --- Marlin/src/feature/controllerfan.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index bc48a6e261..cd56ff8ced 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -58,7 +58,7 @@ class ControllerFan { #if ENABLED(CONTROLLER_FAN_EDITABLE) static controllerFan_settings_t settings; #else - static const controllerFan_settings_t &settings = controllerFan_defaults; + static const controllerFan_settings_t constexpr &settings = controllerFan_defaults; #endif static inline bool state() { return speed > 0; } static inline void init() { reset(); } From 580d314fbe72cd398a90bb62f4e33e186761a9e6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 22 Mar 2020 00:19:05 -0500 Subject: [PATCH 0028/1454] Skip impossible PWM sanity-checks --- Marlin/src/HAL/STM32F1/HAL.h | 1 + Marlin/src/inc/SanityCheck.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index c97abf4bb1..f0f0ce1ea6 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -160,6 +160,7 @@ void HAL_idletask(); #ifndef digitalPinHasPWM #define digitalPinHasPWM(P) (PIN_MAP[P].timer_device != nullptr) + #define NO_COMPILE_TIME_PWM #endif #define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 89b53362d6..f44f93b9af 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1985,7 +1985,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Auto Fan check for PWM pins */ -#if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255 +#if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255 && DISABLED(NO_COMPILE_TIME_PWM) #define AF_ERR_SUFF "_AUTO_FAN_PIN is not a PWM pin. Set EXTRUDER_AUTO_FAN_SPEED to 255." #if HAS_AUTO_FAN_0 static_assert(PWM_PIN(E0_AUTO_FAN_PIN), "E0" AF_ERR_SUFF); From adb7a88428c04fe73d0923ba50782ba726968da7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 23 Mar 2020 17:11:00 -0500 Subject: [PATCH 0029/1454] Fix an unused var warning --- Marlin/src/HAL/LPC1768/HAL.cpp | 4 +--- Marlin/src/HAL/LPC1768/HAL.h | 2 +- Marlin/src/HAL/STM32/HAL.cpp | 2 +- Marlin/src/HAL/STM32/HAL.h | 2 +- Marlin/src/HAL/STM32F1/HAL.cpp | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- 6 files changed, 6 insertions(+), 8 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index f0559d268a..f206ce7adb 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -67,9 +67,7 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { return ind > -1 ? ind : dval; } -void flashFirmware(int16_t value) { - NVIC_SystemReset(); -} +void flashFirmware(const int16_t) { NVIC_SystemReset(); } void HAL_clear_reset_source(void) { #if ENABLED(USE_WATCHDOG) diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index c727877ff3..f5ea629f16 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -195,7 +195,7 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); void HAL_idletask(); #define PLATFORM_M997_SUPPORT -void flashFirmware(int16_t value); +void flashFirmware(const int16_t); /** * set_pwm_frequency diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 5d8c686af3..77f8d27640 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -133,6 +133,6 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRe uint16_t HAL_adc_get_result() { return HAL_adc_result; } -void flashFirmware(int16_t) { NVIC_SystemReset(); } +void flashFirmware(const int16_t) { NVIC_SystemReset(); } #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 9fb40d6121..c310cca74e 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -223,4 +223,4 @@ uint16_t HAL_adc_get_result(); #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) #define PLATFORM_M997_SUPPORT -void flashFirmware(int16_t value); +void flashFirmware(const int16_t); diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index bc5479b60c..01fd2c8fc3 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -388,6 +388,6 @@ void analogWrite(pin_t pin, int pwm_val8) { analogWrite(uint8_t(pin), pwm_val8); } -void flashFirmware(int16_t value) { nvic_sys_reset(); } +void flashFirmware(const int16_t) { nvic_sys_reset(); } #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index f0f0ce1ea6..ff42beb92a 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -288,4 +288,4 @@ void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) #define PLATFORM_M997_SUPPORT -void flashFirmware(int16_t value); +void flashFirmware(const int16_t); From cd4060a99cb11b8cb0915294bb91ea427f89ff33 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 24 Mar 2020 11:55:21 +1300 Subject: [PATCH 0030/1454] Add USB serial support to SERIAL_PORT_2 on DUE (#17245) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/DUE/HAL.h | 1 - Marlin/src/HAL/DUE/MarlinSerial.cpp | 20 +++++--------------- Marlin/src/HAL/DUE/MarlinSerial.h | 12 ++++-------- Marlin/src/HAL/DUE/MarlinSerialUSB.cpp | 12 ++++++++---- Marlin/src/HAL/DUE/MarlinSerialUSB.h | 12 +++++++++--- Marlin/src/inc/Conditionals_LCD.h | 4 ++++ 6 files changed, 30 insertions(+), 31 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 97b94b5db2..90b6fabc05 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -94,7 +94,6 @@ #endif #endif - #include "MarlinSerial.h" #include "MarlinSerialUSB.h" diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index d827def422..d114c75989 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -629,23 +629,13 @@ void MarlinSerial::printFloat(double number, uint8_t digits) { // If not using the USB port as serial port #if SERIAL_PORT >= 0 - - // Preinstantiate - template class MarlinSerial>; - - // Instantiate - MarlinSerial> customizedSerial1; - + template class MarlinSerial>; // Define + MarlinSerial> customizedSerial1; // Instantiate #endif -#ifdef SERIAL_PORT_2 - - // Preinstantiate - template class MarlinSerial>; - - // Instantiate - MarlinSerial> customizedSerial2; - +#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 + template class MarlinSerial>; // Define + MarlinSerial> customizedSerial2; // Instantiate #endif #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index eb26a5644d..fa6a2c7d15 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -172,13 +172,9 @@ struct MarlinSerialCfg { }; #if SERIAL_PORT >= 0 - extern MarlinSerial> customizedSerial1; - -#endif // SERIAL_PORT >= 0 - -#ifdef SERIAL_PORT_2 - - extern MarlinSerial> customizedSerial2; - +#endif + +#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 + extern MarlinSerial> customizedSerial2; #endif diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index 41ffb52ba1..7a020bbaf0 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -29,7 +29,7 @@ #include "../../inc/MarlinConfig.h" -#if SERIAL_PORT == -1 +#if HAS_USB_SERIAL #include "MarlinSerialUSB.h" @@ -283,8 +283,12 @@ void MarlinSerialUSB::printFloat(double number, uint8_t digits) { } // Preinstantiate -MarlinSerialUSB customizedSerial1; - -#endif // SERIAL_PORT == -1 +#if SERIAL_PORT == -1 + MarlinSerialUSB customizedSerial1; +#endif +#if SERIAL_PORT_2 == -1 + MarlinSerialUSB customizedSerial2; +#endif +#endif // HAS_USB_SERIAL #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h index d8b051d37e..9aece901b1 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.h +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.h @@ -28,7 +28,7 @@ #include "../../inc/MarlinConfig.h" -#if SERIAL_PORT == -1 +#if HAS_USB_SERIAL #include @@ -88,6 +88,12 @@ private: static void printFloat(double, uint8_t); }; -extern MarlinSerialUSB customizedSerial1; +#if SERIAL_PORT == -1 + extern MarlinSerialUSB customizedSerial1; +#endif -#endif // SERIAL_PORT == -1 +#if SERIAL_PORT_2 == -1 + extern MarlinSerialUSB customizedSerial2; +#endif + +#endif // HAS_USB_SERIAL diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 2907694fb4..dd1f13fae0 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -683,6 +683,10 @@ #define SPI_SPEED SPI_FULL_SPEED #endif +#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1 + #define HAS_USB_SERIAL 1 +#endif + /** * This setting is also used by M109 when trying to calculate * a ballpark safe margin to prevent wait-forever situation. From e3ebbe25e0f643d0423edf4b5c43db18e54ef5c1 Mon Sep 17 00:00:00 2001 From: George Fu Date: Tue, 24 Mar 2020 07:00:22 +0800 Subject: [PATCH 0031/1454] DGUS updates (#17260) --- Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 10 +++++----- .../src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp | 10 +++++++++- Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h | 1 + 3 files changed, 15 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index 2b4080485f..6ac84c2bb0 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -30,10 +30,6 @@ #error "More than 2 hotends not implemented on the Display UI design." #endif -#include "DGUSDisplay.h" -#include "DGUSVPVariable.h" -#include "DGUSDisplayDef.h" - #include "../../ui_api.h" #include "../../../../MarlinCore.h" @@ -48,6 +44,10 @@ #include "../../../../feature/powerloss.h" #endif +#include "DGUSDisplay.h" +#include "DGUSVPVariable.h" +#include "DGUSDisplayDef.h" + // Preamble... 2 Bytes, usually 0x5A 0xA5, but configurable constexpr uint8_t DGUS_HEADER1 = 0x5A; constexpr uint8_t DGUS_HEADER2 = 0xA5; @@ -855,7 +855,7 @@ void DGUSScreenVariableHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable void DGUSScreenVariableHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("HandleProbeOffsetZChanged"); - const float offset = float(swap16(*(uint16_t*)val_ptr)) / 100.0f; + const float offset = float(int16_t(swap16(*(uint16_t*)val_ptr))) / 100.0f; ExtUI::setZOffset_mm(offset); ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel return; diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp index 3ccde11411..5fbb307ee8 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp @@ -283,6 +283,13 @@ const uint16_t VPList_FLCPrinting[] PROGMEM = { 0x0000 }; +const uint16_t VPList_Z_Offset[] PROGMEM = { + #if HOTENDS >= 1 + VP_SD_Print_ProbeOffsetZ, + #endif + 0x0000 +}; + const struct VPMapping VPMap[] PROGMEM = { { DGUSLCD_SCREEN_BOOT, VPList_Boot }, { DGUSLCD_SCREEN_MAIN, VPList_Main }, @@ -291,6 +298,7 @@ const struct VPMapping VPMap[] PROGMEM = { { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, @@ -361,7 +369,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #if HOTENDS >= 1 VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, DGUSScreenVariableHandler::HandleTemperatureChanged, &DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, nullptr, DGUSScreenVariableHandler::HandleFlowRateChanged, &DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], DGUSScreenVariableHandler::HandleFlowRateChanged, &DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), VPHELPER(VP_MOVE_E0, nullptr, &DGUSScreenVariableHandler::HandleManualExtrude, nullptr), VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &DGUSScreenVariableHandler::HandleHeaterControl, nullptr), diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h index dbf7b8f631..1bfdf54254 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h @@ -35,6 +35,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_FILAMENT_LOADING = 76, DGUSLCD_SCREEN_FILAMENT_UNLOADING = 82, DGUSLCD_SCREEN_MANUALEXTRUDE = 84, + DGUSLCD_SCREEN_Z_OFFSET = 88, DGUSLCD_SCREEN_SDFILELIST = 3, DGUSLCD_SCREEN_SDPRINTMANIPULATION = 7, DGUSLCD_SCREEN_SDPRINTTUNE = 9, From c87d73045b7bb6f05c6e7c149ac07751e7ff963f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 23 Mar 2020 18:31:04 -0500 Subject: [PATCH 0032/1454] Fix extra M114 output line Fixes #17255 --- Marlin/src/module/motion.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index c1d8fceaa0..a0b59284fe 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -218,7 +218,6 @@ inline void report_more_positions() { inline void report_logical_position(const xyze_pos_t &rpos) { const xyze_pos_t lpos = rpos.asLogical(); SERIAL_ECHOPAIR_P(X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z, SP_E_LBL, lpos.e); - report_more_positions(); } // Report the real current position according to the steppers. @@ -237,10 +236,14 @@ void report_real_position() { #endif report_logical_position(npos); + report_more_positions(); } // Report the logical current position according to the most recent G-code command -void report_current_position() { report_logical_position(current_position); } +void report_current_position() { + report_logical_position(current_position); + report_more_positions(); +} /** * Report the logical current position according to the most recent G-code command. From edd6f6c5f293c510069d4f60587e6f9b3ecac939 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 24 Mar 2020 00:03:08 +0000 Subject: [PATCH 0033/1454] [cron] Bump distribution date (2020-03-24) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 22d2ac724c..5fc2211023 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-23" + #define STRING_DISTRIBUTION_DATE "2020-03-24" #endif /** From bef9b9b07e90b5e81e900cb9d740145e8b494e6d Mon Sep 17 00:00:00 2001 From: rado79 <51396577+rado79@users.noreply.github.com> Date: Tue, 24 Mar 2020 02:32:36 +0100 Subject: [PATCH 0034/1454] Delay after homing_backoff for CoreXY sensorless homing (#17273) --- Marlin/src/module/motion.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index a0b59284fe..14da9b47e0 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1779,6 +1779,13 @@ void homeaxis(const AxisEnum axis) { #endif homing_feedrate(axis) ); + + #if ENABLED(SENSORLESS_HOMING) + planner.synchronize(); + #if IS_CORE + if (axis != NORMAL_AXIS) safe_delay(200); // Short delay to allow belts to spring back + #endif + #endif } #endif From 326022800988855b32ede249e0bb134b93466564 Mon Sep 17 00:00:00 2001 From: mkpfalz <50922721+mkpfalz@users.noreply.github.com> Date: Tue, 24 Mar 2020 20:08:55 +0100 Subject: [PATCH 0035/1454] Sanity-check CORE backlash axes (#17279) Co-authored-by: Scott Lahteine --- Marlin/src/inc/SanityCheck.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f44f93b9af..5814d92bb0 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2651,14 +2651,14 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #if ENABLED(BACKLASH_COMPENSATION) - #if IS_CORE - #error "BACKLASH_COMPENSATION is incompatible with CORE kinematics." - #endif #ifndef BACKLASH_DISTANCE_MM #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM" - #endif - #ifndef BACKLASH_CORRECTION + #elif !defined(BACKLASH_CORRECTION) #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION" + #elif IS_CORE + constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; + static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], + "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " with your CORE system."); #endif #endif From 4113481c4eb1c218cc93e7928c024ff01d00bb88 Mon Sep 17 00:00:00 2001 From: MarkMan0 <38912829+MarkMan0@users.noreply.github.com> Date: Tue, 24 Mar 2020 21:13:37 +0100 Subject: [PATCH 0036/1454] Fix limits on acceleration editing (#17280) --- Marlin/src/lcd/menu/menu_advanced.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index ca02dc9622..1577e59fc1 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -376,12 +376,12 @@ void menu_cancelobject(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - static float max_accel = _MAX(planner.settings.max_acceleration_mm_per_s2[A_AXIS], planner.settings.max_acceleration_mm_per_s2[B_AXIS], planner.settings.max_acceleration_mm_per_s2[C_AXIS]); + const float max_accel = _MAX(planner.settings.max_acceleration_mm_per_s2[A_AXIS], planner.settings.max_acceleration_mm_per_s2[B_AXIS], planner.settings.max_acceleration_mm_per_s2[C_AXIS]); // M204 P Acceleration EDIT_ITEM_FAST(float5_25, MSG_ACC, &planner.settings.acceleration, 25, max_accel); // M204 R Retract Acceleration - EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, max_accel); + EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); // M204 T Travel Acceleration EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel); From 41e944da002f38da71deadb092f1803e4501233e Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 25 Mar 2020 09:14:52 +1300 Subject: [PATCH 0037/1454] Fix Emergency Parser on DUE (#17276) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/DUE/HAL.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 90b6fabc05..42f6f175fb 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -39,7 +39,7 @@ #include // Define MYSERIAL0/1 before MarlinSerial includes! -#if SERIAL_PORT == -1 +#if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER) #define MYSERIAL0 customizedSerial1 #elif SERIAL_PORT == 0 #define MYSERIAL0 Serial @@ -56,7 +56,7 @@ #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == SERIAL_PORT #error "SERIAL_PORT_2 must be different from SERIAL_PORT. Please update your configuration." - #elif SERIAL_PORT_2 == -1 + #elif SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER) #define MYSERIAL1 customizedSerial2 #elif SERIAL_PORT_2 == 0 #define MYSERIAL1 Serial From 7455bb09b348c5126d651200f0fae9d00d78cc39 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Mar 2020 16:14:30 -0500 Subject: [PATCH 0038/1454] Add SoftwareSerialM for MKS Robin (#17207) --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 35 ++++++++++++++++++++++++ platformio.ini | 6 ++-- 2 files changed, 39 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index db35548e88..2f2881ee3f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -157,3 +157,38 @@ #define SDSS PD2 #define SD_DETECT_PIN -1 #endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // Unused servo pins may be repurposed with SoftwareSerialM + //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN + //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN + //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN + //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN + //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + //#define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + + // Reduce baud rate for software serial reliability + #if HAS_TMC_SW_SERIAL + #define TMC_BAUD_RATE 19200 + #endif +#endif diff --git a/platformio.ini b/platformio.ini index 62582e1d93..2f3e86c316 100644 --- a/platformio.ini +++ b/platformio.ini @@ -491,7 +491,7 @@ build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_nano.py src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} +lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -502,10 +502,12 @@ lib_ignore = Adafruit NeoPixel, SPI platform = ststm32 board = genericSTM32F103ZE build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DSTM32_XL_DENSITY + ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_XL_DENSITY build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin.py src_filter = ${common.default_src_filter} + +lib_deps = ${common.lib_deps} + SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI # From 68face848ab75f987ce4b679064f3546715afb20 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Mar 2020 16:40:40 -0500 Subject: [PATCH 0039/1454] Sanity check CONTROLLERFAN_SECS --- Marlin/src/inc/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 5814d92bb0..2fd61d4be1 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -272,6 +272,8 @@ #error "CONTROLLERFAN_PIN is now CONTROLLER_FAN_PIN, enabled with USE_CONTROLLER_FAN. Please update your Configuration_adv.h." #elif defined(CONTROLLERFAN_SPEED) #error "CONTROLLERFAN_SPEED is now CONTROLLERFAN_SPEED_ACTIVE. Please update your Configuration_adv.h." +#elif defined(CONTROLLERFAN_SECS) + #error "CONTROLLERFAN_SECS is now CONTROLLERFAN_IDLE_TIME. Please update your Configuration_adv.h." #elif defined(MIN_RETRACT) #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT. Please update your Configuration_adv.h." #elif defined(ADVANCE) From 5d515c3a2fac22b7adc0222f64aac6dbf7be7eed Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Tue, 24 Mar 2020 17:08:31 -0500 Subject: [PATCH 0040/1454] Adjust for timing shift on Max7219 displays on AVR's Something has shifted. The previous timing delays on the Max7219 debug displays is too tight without this correction. I suspect something has been optimized and roughly 50ns of needed setup and hold time has disappeared. This corrects the issue and the display results are clean again. --- Marlin/src/feature/max7219.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 2ec23f019c..b37ba98e7e 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -121,7 +121,7 @@ uint8_t Max7219::suspended; // = 0; #define CRITICAL_SECTION_START() NOOP #define CRITICAL_SECTION_END() NOOP #else - #define SIG_DELAY() DELAY_NS(188) // Delay for 0.1875µs (16MHz AVR) or 0.15µs (20MHz AVR) + #define SIG_DELAY() DELAY_NS(250) // Delay for 0.1875µs (16MHz AVR) or 0.15µs (20MHz AVR) #endif void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) { From 7124b2164d5c863ed1013df57a424739420003fc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Mar 2020 16:22:12 -0500 Subject: [PATCH 0041/1454] Version 2.0.5.2 --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- config/README.md | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 8cd3beb2df..91cc6144cd 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.0.5.1" +//#define SHORT_BUILD_VERSION "2.0.5.2" /** * Verbose version identifier which should contain a reference to the location diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2d4e453d0b..6022c16672 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.0.5.1" + #define SHORT_BUILD_VERSION "2.0.5.2" #endif /** diff --git a/config/README.md b/config/README.md index f4dfd9aedf..284a856215 100644 --- a/config/README.md +++ b/config/README.md @@ -1,3 +1,3 @@ # Where have all the configurations gone? -## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.5.zip +## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.5.2.zip From 075a86b076719e0d0cb3d390c71b590a6f3a3750 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Tue, 24 Mar 2020 17:15:03 -0500 Subject: [PATCH 0042/1454] Update LCD timing on Formbot T-Rex 2+ machines The code is slightly more optimized than it used to be and this has caused the setup and hold times on the Formbot T-Rex 2+ machines to be insufficient. This change gives sufficient margin and the LCD Display is clean again. --- Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 8fa3686514..5176c699ee 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -21,6 +21,15 @@ */ #pragma once +/** + * Override default LCD timing for Formbot T-Rex 2+ machines. + * The long LCD cables and the routing near electrically noisy stepper motors + * requires a slightly longer setup and hold time on the signals. + */ +#define BOARD_ST7920_DELAY_1 DELAY_NS(200) +#define BOARD_ST7920_DELAY_2 DELAY_NS(200) +#define BOARD_ST7920_DELAY_3 DELAY_NS(200) + /** * Formbot pin assignments */ From 0aeee64cca2364be6025c58bbf1970ff4c77e710 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 25 Mar 2020 00:03:18 +0000 Subject: [PATCH 0043/1454] [cron] Bump distribution date (2020-03-25) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5fc2211023..e9ac62d04f 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-24" + #define STRING_DISTRIBUTION_DATE "2020-03-25" #endif /** From 1986e1cdf851579958dc1fb245486cb2099582dc Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Tue, 24 Mar 2020 19:38:09 -0500 Subject: [PATCH 0044/1454] Allow PID_DEBUG to be turned on and off (#17284) M303 D will now toggle activation of PID_DEBUG output. This allows the debug capability to be built into the firmware, but turned on and off as needed. --- Marlin/Configuration.h | 2 +- Marlin/src/gcode/temp/M303.cpp | 16 ++++++++++++++++ Marlin/src/module/temperature.cpp | 18 ++++++------------ 3 files changed, 23 insertions(+), 13 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index df99f8b676..77c077ed42 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -473,7 +473,7 @@ #if ENABLED(PIDTEMP) //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM) //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) - //#define PID_DEBUG // Sends debug data to the serial port. + //#define PID_DEBUG // Sends debug data to the serial port. Use M303 D to toggle activation. //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 63dcc3f4c4..ba119f0d41 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -38,7 +38,13 @@ * E (-1 for the bed) (default 0) * C Minimum 3. Default 5. * U with a non-zero value will apply the result to current settings + * D Toggles PID_DEBUG flag. No other action happens even if more parameters are specified. */ + +#if ENABLED(PID_DEBUG) + bool PID_Debug_Flag = 0; +#endif + void GcodeSuite::M303() { #if ENABLED(PIDTEMPBED) #define SI H_BED @@ -63,6 +69,16 @@ void GcodeSuite::M303() { const bool u = parser.boolval('U'); const int16_t temp = parser.celsiusval('S', e < 0 ? 70 : 150); + #if ENABLED(PID_DEBUG) + bool d = parser.boolval('D'); + if (d) { + PID_Debug_Flag = !PID_Debug_Flag; + SERIAL_ECHOPGM("PID Debug set to: "); + SERIAL_ECHOLN( PID_Debug_Flag ); + return; + } + #endif + #if DISABLED(BUSY_WHILE_HEATING) KEEPALIVE_STATE(NOT_BUSY); #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f16a3af046..4e49fcfa24 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -830,6 +830,9 @@ void Temperature::min_temp_error(const heater_ind_t heater) { } #if HOTENDS + #if ENABLED(PID_DEBUG) + extern bool PID_Debug_Flag; + #endif float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; @@ -911,24 +914,15 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #endif // PID_OPENLOOP #if ENABLED(PID_DEBUG) - if (ee == active_extruder) { + if (ee == active_extruder && PID_Debug_Flag) { SERIAL_ECHO_START(); - SERIAL_ECHOPAIR( - STR_PID_DEBUG, ee, - STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, - STR_PID_DEBUG_OUTPUT, pid_output - ); + SERIAL_ECHOPAIR(STR_PID_DEBUG, ee, STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, STR_PID_DEBUG_OUTPUT, pid_output); #if DISABLED(PID_OPENLOOP) - { - SERIAL_ECHOPAIR( - STR_PID_DEBUG_PTERM, work_pid[ee].Kp, - STR_PID_DEBUG_ITERM, work_pid[ee].Ki, - STR_PID_DEBUG_DTERM, work_pid[ee].Kd + SERIAL_ECHOPAIR( STR_PID_DEBUG_PTERM, work_pid[ee].Kp, STR_PID_DEBUG_ITERM, work_pid[ee].Ki, STR_PID_DEBUG_DTERM, work_pid[ee].Kd #if ENABLED(PID_EXTRUSION_SCALING) , STR_PID_DEBUG_CTERM, work_pid[ee].Kc #endif ); - } #endif SERIAL_EOL(); } From f2ed18d150a070b5542b6113c8bea6e62a31ab02 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 15:07:58 -0500 Subject: [PATCH 0045/1454] M303 followup - Put 'D' before other params for clean exit. - Use serial on/off for debug status. --- Marlin/Configuration.h | 2 +- Marlin/src/gcode/temp/M303.cpp | 35 ++++++++++++++++++---------------- 2 files changed, 20 insertions(+), 17 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 77c077ed42..f02e69ee5a 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -473,7 +473,7 @@ #if ENABLED(PIDTEMP) //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM) //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) - //#define PID_DEBUG // Sends debug data to the serial port. Use M303 D to toggle activation. + //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index ba119f0d41..657dd867ee 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -34,18 +34,31 @@ /** * M303: PID relay autotune * - * S sets the target temperature. (default 150C / 70C) - * E (-1 for the bed) (default 0) - * C Minimum 3. Default 5. - * U with a non-zero value will apply the result to current settings - * D Toggles PID_DEBUG flag. No other action happens even if more parameters are specified. + * S Set the target temperature. (Default: 150C / 70C) + * E Extruder number to tune, or -1 for the bed. (Default: E0) + * C Number of times to repeat the procedure. (Minimum: 3, Default: 5) + * U Flag to apply the result to the current PID values + * + * With PID_DEBUG: + * D Toggle PID debugging and EXIT without further action. */ #if ENABLED(PID_DEBUG) - bool PID_Debug_Flag = 0; + bool pid_debug_flag = 0; #endif void GcodeSuite::M303() { + + #if ENABLED(PID_DEBUG) + if (parser.seen('D')) { + pid_debug_flag = !pid_debug_flag; + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("PID Debug "); + serialprintln_onoff(pid_debug_flag); + return; + } + #endif + #if ENABLED(PIDTEMPBED) #define SI H_BED #else @@ -69,16 +82,6 @@ void GcodeSuite::M303() { const bool u = parser.boolval('U'); const int16_t temp = parser.celsiusval('S', e < 0 ? 70 : 150); - #if ENABLED(PID_DEBUG) - bool d = parser.boolval('D'); - if (d) { - PID_Debug_Flag = !PID_Debug_Flag; - SERIAL_ECHOPGM("PID Debug set to: "); - SERIAL_ECHOLN( PID_Debug_Flag ); - return; - } - #endif - #if DISABLED(BUSY_WHILE_HEATING) KEEPALIVE_STATE(NOT_BUSY); #endif From c86ee574ec7495e926bdfa52d68571758fba7a59 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 15:11:02 -0500 Subject: [PATCH 0046/1454] Drop old comment --- Marlin/src/feature/max7219.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index b37ba98e7e..a012aeb5fa 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -121,7 +121,7 @@ uint8_t Max7219::suspended; // = 0; #define CRITICAL_SECTION_START() NOOP #define CRITICAL_SECTION_END() NOOP #else - #define SIG_DELAY() DELAY_NS(250) // Delay for 0.1875µs (16MHz AVR) or 0.15µs (20MHz AVR) + #define SIG_DELAY() DELAY_NS(250) #endif void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) { From 4dea0200500bedb2c9dd9e90ad74cc9fd845edd9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 26 Mar 2020 00:03:54 +0000 Subject: [PATCH 0047/1454] [cron] Bump distribution date (2020-03-26) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e9ac62d04f..7025c695a1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-25" + #define STRING_DISTRIBUTION_DATE "2020-03-26" #endif /** From adb6334ba031166e33f256344fc2b01e909cd99f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 17:55:36 -0500 Subject: [PATCH 0048/1454] Use "dist" instead of "delta" for clarity --- Marlin/src/feature/backlash.cpp | 2 +- Marlin/src/module/motion.cpp | 9 ++-- Marlin/src/module/planner.cpp | 96 ++++++++++++++++----------------- Marlin/src/module/planner.h | 24 +++++---- 4 files changed, 68 insertions(+), 63 deletions(-) diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 84cd0a85b7..bc33ae3185 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -113,7 +113,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps } #endif - // Making a correction reduces the residual error and modifies delta_mm + // Making a correction reduces the residual error and adds block steps if (error_correction) { block->steps[axis] += ABS(error_correction); residual_error[axis] -= error_correction; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 14da9b47e0..8ab96b9b08 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1292,12 +1292,14 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { */ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t fr_mm_s=0.0) { + const feedRate_t real_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR(">>> do_homing_move(", axis_codes[axis], ", ", distance, ", "); if (fr_mm_s) DEBUG_ECHO(fr_mm_s); else - DEBUG_ECHOPAIR("[", homing_feedrate(axis), "]"); + DEBUG_ECHOPAIR("[", real_fr_mm_s, "]"); DEBUG_ECHOLNPGM(")"); } @@ -1331,7 +1333,6 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t #endif } - const feedRate_t real_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); #if IS_SCARA // Tell the planner the axis is at 0 current_position[axis] = 0; @@ -1345,13 +1346,13 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t target[axis] = distance; #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - const xyze_float_t delta_mm_cart{0}; + const xyze_float_t cart_dist_mm{0}; #endif // Set delta/cartesian axes directly planner.buffer_segment(target #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + , cart_dist_mm #endif , real_fr_mm_s, active_extruder ); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 3b2daf1812..c71a0f61cc 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1648,8 +1648,8 @@ bool Planner::_buffer_steps(const xyze_long_t &target #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters ) { @@ -1666,8 +1666,8 @@ bool Planner::_buffer_steps(const xyze_long_t &target #if HAS_POSITION_FLOAT , target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , fr_mm_s, extruder, millimeters )) { @@ -1712,8 +1712,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ ) { @@ -1840,51 +1840,51 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * So we need to create other 2 "AXIS", named X_HEAD and Y_HEAD, meaning the real displacement of the Head. * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ - struct DeltaMM : abce_float_t { + struct DistanceMM : abce_float_t { #if IS_CORE xyz_pos_t head; #endif - } delta_mm; + } steps_dist_mm; #if IS_CORE #if CORE_IS_XY - delta_mm.head.x = da * steps_to_mm[A_AXIS]; - delta_mm.head.y = db * steps_to_mm[B_AXIS]; - delta_mm.z = dc * steps_to_mm[Z_AXIS]; - delta_mm.a = (da + db) * steps_to_mm[A_AXIS]; - delta_mm.b = CORESIGN(da - db) * steps_to_mm[B_AXIS]; + steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; + steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; + steps_dist_mm.z = dc * steps_to_mm[Z_AXIS]; + steps_dist_mm.a = (da + db) * steps_to_mm[A_AXIS]; + steps_dist_mm.b = CORESIGN(da - db) * steps_to_mm[B_AXIS]; #elif CORE_IS_XZ - delta_mm.head.x = da * steps_to_mm[A_AXIS]; - delta_mm.y = db * steps_to_mm[Y_AXIS]; - delta_mm.head.z = dc * steps_to_mm[C_AXIS]; - delta_mm.a = (da + dc) * steps_to_mm[A_AXIS]; - delta_mm.c = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; + steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; + steps_dist_mm.y = db * steps_to_mm[Y_AXIS]; + steps_dist_mm.head.z = dc * steps_to_mm[C_AXIS]; + steps_dist_mm.a = (da + dc) * steps_to_mm[A_AXIS]; + steps_dist_mm.c = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; #elif CORE_IS_YZ - delta_mm.x = da * steps_to_mm[X_AXIS]; - delta_mm.head.y = db * steps_to_mm[B_AXIS]; - delta_mm.head.z = dc * steps_to_mm[C_AXIS]; - delta_mm.b = (db + dc) * steps_to_mm[B_AXIS]; - delta_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; + steps_dist_mm.x = da * steps_to_mm[X_AXIS]; + steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; + steps_dist_mm.head.z = dc * steps_to_mm[C_AXIS]; + steps_dist_mm.b = (db + dc) * steps_to_mm[B_AXIS]; + steps_dist_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif #else - delta_mm.a = da * steps_to_mm[A_AXIS]; - delta_mm.b = db * steps_to_mm[B_AXIS]; - delta_mm.c = dc * steps_to_mm[C_AXIS]; + steps_dist_mm.a = da * steps_to_mm[A_AXIS]; + steps_dist_mm.b = db * steps_to_mm[B_AXIS]; + steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; #endif #if EXTRUDERS - delta_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; + steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; #else - delta_mm.e = 0.0f; + steps_dist_mm.e = 0.0f; #endif #if ENABLED(LCD_SHOW_E_TOTAL) - e_move_accumulator += delta_mm.e; + e_move_accumulator += steps_dist_mm.e; #endif if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { block->millimeters = (0 #if EXTRUDERS - + ABS(delta_mm.e) + + ABS(steps_dist_mm.e) #endif ); } @@ -1894,13 +1894,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, else block->millimeters = SQRT( #if CORE_IS_XY - sq(delta_mm.head.x) + sq(delta_mm.head.y) + sq(delta_mm.z) + sq(steps_dist_mm.head.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.z) #elif CORE_IS_XZ - sq(delta_mm.head.x) + sq(delta_mm.y) + sq(delta_mm.head.z) + sq(steps_dist_mm.head.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.head.z) #elif CORE_IS_YZ - sq(delta_mm.x) + sq(delta_mm.head.y) + sq(delta_mm.head.z) + sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) #else - sq(delta_mm.x) + sq(delta_mm.y) + sq(delta_mm.z) + sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.z) #endif ); @@ -2071,7 +2071,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(FILAMENT_WIDTH_SENSOR) if (extruder == FILAMENT_SENSOR_EXTRUDER_NUM) // Only for extruder with filament sensor - filwidth.advance_e(delta_mm.e); + filwidth.advance_e(steps_dist_mm.e); #endif // Calculate and limit speed in mm/sec @@ -2081,7 +2081,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Linear axes first with less logic LOOP_XYZ(i) { - current_speed[i] = delta_mm[i] * inverse_secs; + current_speed[i] = steps_dist_mm[i] * inverse_secs; const feedRate_t cs = ABS(current_speed[i]), max_fr = settings.max_feedrate_mm_s[i]; if (cs > max_fr) NOMORE(speed_factor, max_fr / cs); @@ -2090,7 +2090,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Limit speed on extruders, if any #if EXTRUDERS { - current_speed.e = delta_mm.e * inverse_secs; + current_speed.e = steps_dist_mm.e * inverse_secs; #if BOTH(MIXING_EXTRUDER, RETRACT_SYNC_MIXING) // Move all mixing extruders at the specified rate if (mixer.get_current_vtool() == MIXER_AUTORETRACT_TOOL) @@ -2308,10 +2308,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, static xyze_float_t prev_unit_vec; xyze_float_t unit_vec = - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - delta_mm_cart + #if HAS_DIST_MM_ARG + cart_dist_mm #else - { delta_mm.x, delta_mm.y, delta_mm.z, delta_mm.e } + { steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.e } #endif ; unit_vec *= inverse_millimeters; @@ -2572,8 +2572,8 @@ void Planner::buffer_sync_block() { * millimeters - the length of the movement, if known */ bool Planner::buffer_segment(const float &a, const float &b, const float &c, const float &e - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ ) { @@ -2651,8 +2651,8 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con #if HAS_POSITION_FLOAT , target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , fr_mm_s, extruder, millimeters ) @@ -2686,17 +2686,17 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #if IS_KINEMATIC #if DISABLED(CLASSIC_JERK) - const xyze_pos_t delta_mm_cart = { + const xyze_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z, e - position_cart.e }; #else - const xyz_pos_t delta_mm_cart = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; + const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; #endif float mm = millimeters; if (mm == 0.0) - mm = (delta_mm_cart.x != 0.0 || delta_mm_cart.y != 0.0) ? delta_mm_cart.magnitude() : ABS(delta_mm_cart.z); + mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z); // Cartesian XYZ to kinematic ABC, stored in global 'delta' inverse_kinematics(machine); @@ -2712,7 +2712,7 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #endif if (buffer_segment(delta.a, delta.b, delta.c, machine.e #if DISABLED(CLASSIC_JERK) - , delta_mm_cart + , cart_dist_mm #endif , feedrate, extruder, mm )) { diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ae104eb354..24c02c01c5 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -61,6 +61,10 @@ manual_feedrate_mm_s { _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, _mf.e / 60.0f }; #endif +#if IS_KINEMATIC && DISABLED(CLASSIC_JERK) + #define HAS_DIST_MM_ARG 1 +#endif + enum BlockFlagBit : char { // Recalculate trapezoids on entry junction. For optimization. BLOCK_BIT_RECALCULATE, @@ -588,8 +592,8 @@ class Planner { #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); @@ -611,8 +615,8 @@ class Planner { #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); @@ -643,21 +647,21 @@ class Planner { * millimeters - the length of the movement, if known */ static bool buffer_segment(const float &a, const float &b, const float &c, const float &e - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); FORCE_INLINE static bool buffer_segment(abce_pos_t &abce - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ) { return buffer_segment(abce.a, abce.b, abce.c, abce.e - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , fr_mm_s, extruder, millimeters); } From 0175189c34807733c2230d36e470a713a8186d49 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 19:17:50 -0500 Subject: [PATCH 0049/1454] Allow G2_PWM to be slimmer --- Marlin/src/HAL/DUE/fastio/G2_PWM.cpp | 147 +++++++++++++++------- Marlin/src/module/configuration_store.cpp | 2 +- 2 files changed, 105 insertions(+), 44 deletions(-) diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp index fd2c6ccf97..672932f56c 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp @@ -46,6 +46,31 @@ #include "G2_PWM.h" +#if PIN_EXISTS(MOTOR_CURRENT_PWM_X) + #define G2_PWM_X 1 +#else + #define G2_PWM_X 0 +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_Y) + #define G2_PWM_Y 1 +#else + #define G2_PWM_Y 0 +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + #define G2_PWM_Z 1 +#else + #define G2_PWM_Z 0 +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + #define G2_PWM_E 1 +#else + #define G2_PWM_E 0 +#endif +#define G2_MASK_X(V) (G2_PWM_X * (V)) +#define G2_MASK_Y(V) (G2_PWM_Y * (V)) +#define G2_MASK_Z(V) (G2_PWM_Z * (V)) +#define G2_MASK_E(V) (G2_PWM_E * (V)) + volatile uint32_t *SODR_A = &PIOA->PIO_SODR, *SODR_B = &PIOB->PIO_SODR, *CODR_A = &PIOA->PIO_CODR, @@ -55,10 +80,18 @@ PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT; void Stepper::digipot_init() { - OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins - OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0); - OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0); - OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0); + #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) + OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y) + OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0); + #endif + #if G2_PWM_Z + OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0); + #endif + #if G2_PWM_E + OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0); + #endif #define WPKEY (0x50574D << 8) // “PWM” in ASCII #define WPCMD_DIS_SW 0 // command to disable Write Protect SW @@ -71,30 +104,51 @@ void Stepper::digipot_init() { PWM->PWM_WPCR = WPKEY | WPRG_ALL | WPCMD_DIS_SW; // enable setting of all PWM registers PWM->PWM_CLK = PWM_CLOCK_F; // enable CLK_A and set it to 1MHz, leave CLK_B disabled PWM->PWM_CH_NUM[0].PWM_CMR = 0b1011; // set channel 0 to Clock A input & to left aligned - PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned - PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned - PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned - PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned + if (G2_PWM_X) PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned + if (G2_PWM_Y) PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned + if (G2_PWM_Z) PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned + if (G2_PWM_E) PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned PWM->PWM_CH_NUM[0].PWM_CPRD = PWM_PERIOD_US; // set channel 0 Period PWM->PWM_IER2 = PWM_IER1_CHID0; // generate interrupt when counter0 overflows - PWM->PWM_IER2 = PWM_IER2_CMPM0 | PWM_IER2_CMPM1 | PWM_IER2_CMPM2 | PWM_IER2_CMPM3 | PWM_IER2_CMPM4; // generate interrupt on compare event + PWM->PWM_IER2 = PWM_IER2_CMPM0 + | G2_MASK_X(PWM_IER2_CMPM1) + | G2_MASK_Y(PWM_IER2_CMPM2) + | G2_MASK_Z(PWM_IER2_CMPM3) + | G2_MASK_E(PWM_IER2_CMPM4) + ; // generate interrupt on compare event - PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive - PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive - PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive - PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive + if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive + if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive - PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0 | PWM_SCM_SYNC1 | PWM_SCM_SYNC2 | PWM_SCM_SYNC3 | PWM_SCM_SYNC4; // sync 1-4 with 0, use mode 0 for updates + PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0 + | G2_MASK_X(PWM_SCM_SYNC1) + | G2_MASK_Y(PWM_SCM_SYNC2) + | G2_MASK_Z(PWM_SCM_SYNC3) + | G2_MASK_E(PWM_SCM_SYNC4) + ; // sync 1-4 with 0, use mode 0 for updates - PWM->PWM_ENA = PWM_ENA_CHID0 | PWM_ENA_CHID1 | PWM_ENA_CHID2 | PWM_ENA_CHID3 | PWM_ENA_CHID4; // enable the channels used by G2 - PWM->PWM_IER1 = PWM_IER1_CHID0 | PWM_IER1_CHID1 | PWM_IER1_CHID2 | PWM_IER1_CHID3 | PWM_IER1_CHID4; // enable interrupts for the channels used by G2 + PWM->PWM_ENA = PWM_ENA_CHID0 + | G2_MASK_X(PWM_ENA_CHID1) + | G2_MASK_Y(PWM_ENA_CHID2) + | G2_MASK_Z(PWM_ENA_CHID3) + | G2_MASK_E(PWM_ENA_CHID4) + ; // enable channels used by G2 + + PWM->PWM_IER1 = PWM_IER1_CHID0 + | G2_MASK_X(PWM_IER1_CHID1) + | G2_MASK_Y(PWM_IER1_CHID2) + | G2_MASK_Z(PWM_IER1_CHID3) + | G2_MASK_E(PWM_IER1_CHID4) + ; // enable interrupts for channels used by G2 NVIC_EnableIRQ(PWM_IRQn); // Enable interrupt handler NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals) @@ -105,20 +159,27 @@ void Stepper::digipot_current(const uint8_t driver, const int16_t current) { if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed switch (driver) { - case 0: PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y - PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); - PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle - break; - case 1: PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z - PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle - break; - default:PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E - PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle - break; + case 0: + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event + if (G2_PWM_X || G2_PWM_Y) PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle + break; + case 1: + if (G2_PWM_Z) { + PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z + PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event + PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle + } + break; + default: + if (G2_PWM_E) { + PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E + PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event + PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle + } + break; } } @@ -127,17 +188,17 @@ volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS; void PWM_Handler() { PWM_ISR1_STATUS = PWM->PWM_ISR1; PWM_ISR2_STATUS = PWM->PWM_ISR2; - if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt - *ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active - *ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active - *ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active - *ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active + if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt + if (G2_PWM_X) *ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active + if (G2_PWM_Y) *ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active + if (G2_PWM_Z) *ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active + if (G2_PWM_E) *ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active } else { - if (PWM_ISR2_STATUS & PWM_IER2_CMPM1) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive - if (PWM_ISR2_STATUS & PWM_IER2_CMPM2) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive - if (PWM_ISR2_STATUS & PWM_IER2_CMPM3) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive - if (PWM_ISR2_STATUS & PWM_IER2_CMPM4) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive + if (G2_PWM_X && (PWM_ISR2_STATUS & PWM_IER2_CMPM1)) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive + if (G2_PWM_Y && (PWM_ISR2_STATUS & PWM_IER2_CMPM2)) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive + if (G2_PWM_Z && (PWM_ISR2_STATUS & PWM_IER2_CMPM3)) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive + if (G2_PWM_E && (PWM_ISR2_STATUS & PWM_IER2_CMPM4)) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive } return; } diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 4b7946c6a9..803095811e 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -2696,7 +2696,7 @@ void MarlinSettings::reset() { #if HAS_MOTOR_CURRENT_PWM constexpr uint32_t tmp_motor_current_setting[3] = PWM_MOTOR_CURRENT; - for (uint8_t q = 3; q--;) + LOOP_L_N(q, 3) stepper.digipot_current(q, (stepper.motor_current_setting[q] = tmp_motor_current_setting[q])); #endif From dd6781217a1571c31124cc5c331a0c39de1ce4fe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 19:21:48 -0500 Subject: [PATCH 0050/1454] motion.cpp: HAS_DIST_MM_ARG --- Marlin/src/module/motion.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 8ab96b9b08..e47727b3ec 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1345,13 +1345,13 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t planner.set_machine_position_mm(target); target[axis] = distance; - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) + #if HAS_DIST_MM_ARG const xyze_float_t cart_dist_mm{0}; #endif // Set delta/cartesian axes directly planner.buffer_segment(target - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) + #if HAS_DIST_MM_ARG , cart_dist_mm #endif , real_fr_mm_s, active_extruder From 5ec1a8bb2b0708c3f94f162e71621f662554ce6f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 14:51:22 -0500 Subject: [PATCH 0051/1454] Fix M0 unused var warning --- Marlin/src/gcode/lcd/M0_M1.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 2176693209..20ce55bd78 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -56,9 +56,11 @@ void GcodeSuite::M0_M1() { planner.synchronize(); - const bool seenQ = parser.seen('Q'); - #if HAS_LEDS_OFF_FLAG - if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed + #if HAS_LCD_MENU || HAS_LEDS_OFF_FLAG + const bool seenQ = parser.seen('Q'); + #if HAS_LEDS_OFF_FLAG + if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed + #endif #endif #if HAS_LCD_MENU From 5c150c0c941d9ab3fd140e0a837dff40432acca3 Mon Sep 17 00:00:00 2001 From: Acenotass <44540957+Acenotass@users.noreply.github.com> Date: Thu, 26 Mar 2020 08:04:57 +0600 Subject: [PATCH 0052/1454] Update Russian language (#17290) --- Marlin/src/lcd/language/language_ru.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 82c91c6502..a7c971e8c7 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -222,6 +222,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Кулер ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Кулер доп."); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Кулер доп. ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Обдув платы"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Обороты простоя"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Автовключение"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Рабочие обороты"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Простой после"); PROGMEM Language_Str MSG_FLOW = _UxGT("Поток"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Поток ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Настройки"); From 8122468a361cf9fd25261dc04fa82a9ce1796644 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Thu, 26 Mar 2020 03:05:36 +0100 Subject: [PATCH 0053/1454] Update Italian language (#17293) --- Marlin/src/lcd/language/language_it.h | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index ae4dd813ea..8d8112d523 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -245,6 +245,11 @@ namespace Language_it { PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventola mem. ~"); // Max 15 characters PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra vel.vent."); // Max 15 characters PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra v.vent. ~"); // Max 15 characters + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controller vent."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Vel. inattivo"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo autom."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Vel. attivo"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo inattivo"); PROGMEM Language_Str MSG_FLOW = _UxGT("Flusso"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flusso ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Controllo"); @@ -312,6 +317,9 @@ namespace Language_it { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Carica impostazioni"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ripristina imp."); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inizializza EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: CRC EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: Indice EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versione EEPROM"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aggiorna media"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetta stampante"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna"); From d6a4c3079dc261b94aeccfc5f2031b589744bc67 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 20:47:27 -0500 Subject: [PATCH 0054/1454] Tweak ui.finish_status --- Marlin/src/lcd/ultralcd.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 1cb23baa25..7ff1440559 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -524,7 +524,7 @@ void MarlinUI::status_screen() { #if PROGRESS_MSG_EXPIRE > 0 // Handle message expire - if (expire_status_ms > 0) { + if (expire_status_ms) { // Expire the message if a job is active and the bar has ticks if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { @@ -1337,15 +1337,19 @@ void MarlinUI::update() { UNUSED(persist); #endif + #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + const millis_t ms = millis(); + #endif + #if ENABLED(LCD_PROGRESS_BAR) - progress_bar_ms = millis(); + progress_bar_ms = ms; #if PROGRESS_MSG_EXPIRE > 0 - expire_status_ms = persist ? 0 : progress_bar_ms + PROGRESS_MSG_EXPIRE; + expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; #endif #endif #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = millis() + 5000UL; // Show status message for 5s + next_filament_display = ms + 5000UL; // Show status message for 5s #endif #if HAS_SPI_LCD && ENABLED(STATUS_MESSAGE_SCROLLING) From 54a12ee1d6557d820fb353a318525aebd7f6c082 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Mar 2020 17:20:23 -0500 Subject: [PATCH 0055/1454] Tweak eeprom storage type --- Marlin/src/module/configuration_store.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 803095811e..129e207d29 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -1231,7 +1231,7 @@ void MarlinSettings::postprocess() { #if HAS_MOTOR_CURRENT_PWM EEPROM_WRITE(stepper.motor_current_setting); #else - const xyz_ulong_t no_current{0}; + const uint32_t no_current[3] = { 0 }; EEPROM_WRITE(no_current); #endif } From 98ef161bfe7545afda2c1ab432aeb420637eedde Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 27 Mar 2020 00:03:27 +0000 Subject: [PATCH 0056/1454] [cron] Bump distribution date (2020-03-27) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7025c695a1..afbb5cf3c8 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-26" + #define STRING_DISTRIBUTION_DATE "2020-03-27" #endif /** From 3655e240f5796a84d4e89b3524484e37091efad2 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Fri, 27 Mar 2020 17:06:39 -0400 Subject: [PATCH 0057/1454] Fix SD finished ExtUI / host action (#17285) --- Marlin/src/MarlinCore.cpp | 5 +++-- Marlin/src/gcode/lcd/M0_M1.cpp | 22 +++++++++++----------- Marlin/src/inc/Conditionals_adv.h | 2 +- 3 files changed, 15 insertions(+), 14 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 0ea1a22fd8..7adc8272ea 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -423,7 +423,8 @@ void startOrResumeJob() { switch (card.sdprinting_done_state) { case 1: - did_state = print_job_timer.duration() < 60 || queue.enqueue_one_P(PSTR("M31")); + if (print_job_timer.duration() > 60) + did_state = queue.enqueue_one_P(PSTR("M31")); break; case 2: @@ -437,7 +438,7 @@ void startOrResumeJob() { break; case 4: // Display "Click to Continue..." - #if HAS_RESUME_CONTINUE // 30 min timeout with LCD, 1 min without + #if HAS_LEDS_OFF_FLAG // 30 min timeout with LCD, 1 min without did_state = queue.enqueue_one_P( print_job_timer.duration() < 60 ? PSTR("M0Q1P1") : PSTR("M0Q1S" TERN(HAS_LCD_MENU, "1800", "60")) ); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 20ce55bd78..43b39226f7 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -56,11 +56,11 @@ void GcodeSuite::M0_M1() { planner.synchronize(); - #if HAS_LCD_MENU || HAS_LEDS_OFF_FLAG + #if HAS_LEDS_OFF_FLAG const bool seenQ = parser.seen('Q'); - #if HAS_LEDS_OFF_FLAG - if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed - #endif + if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed + #else + constexpr bool seenQ = false; #endif #if HAS_LCD_MENU @@ -75,12 +75,12 @@ void GcodeSuite::M0_M1() { } #elif ENABLED(EXTENSIBLE_UI) - - if (parser.string_arg) - ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? - else - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); - + if (!seenQ) { + if (parser.string_arg) + ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? + else + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); + } #else if (parser.string_arg) { @@ -94,7 +94,7 @@ void GcodeSuite::M0_M1() { wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); + if (!seenQ) host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); #endif if (ms > 0) ms += millis(); // wait until this time for a click diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 09de5d89d7..a52ae1af29 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -93,7 +93,7 @@ #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS 1 #endif -#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER) +#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS) #define HAS_RESUME_CONTINUE 1 #endif From 129b270628781eae776764e63fd514553e6c2204 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Fri, 27 Mar 2020 23:29:17 +0100 Subject: [PATCH 0058/1454] QSPI EEPROM for SAMD51 (#17292) --- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- Marlin/src/HAL/DUE/EepromEmulation.cpp | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- Marlin/src/HAL/DUE/inc/Conditionals_post.h | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 2 +- Marlin/src/HAL/ESP32/inc/Conditionals_post.h | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 2 +- .../{persistent_store_api.h => eeprom_api.h} | 2 +- ...stent_store_flash.cpp => eeprom_flash.cpp} | 2 +- ...ent_store_sdcard.cpp => eeprom_sdcard.cpp} | 2 +- .../src/HAL/LPC1768/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/SAMD51/QSPIFlash.cpp | 78 +++++++++++ Marlin/src/HAL/SAMD51/QSPIFlash.h | 51 +++++++ Marlin/src/HAL/SAMD51/eeprom.cpp | 66 +++++++++ Marlin/src/HAL/SAMD51/eeprom_flash.cpp | 96 +++++++++++++ Marlin/src/HAL/SAMD51/eeprom_qspi.cpp | 71 ++++++++++ Marlin/src/HAL/SAMD51/inc/Conditionals_post.h | 4 +- .../HAL/SAMD51/persistent_store_eeprom.cpp | 129 ------------------ ...stent_store_flash.cpp => eeprom_flash.cpp} | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 12 +- ...ent_store_sdcard.cpp => eeprom_sdcard.cpp} | 2 +- Marlin/src/HAL/STM32/inc/Conditionals_post.h | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 6 +- ...stent_store_flash.cpp => eeprom_flash.cpp} | 7 +- ...ent_store_sdcard.cpp => eeprom_sdcard.cpp} | 3 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- .../HAL/STM32_F4_F7/inc/Conditionals_post.h | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 2 +- .../HAL/TEENSY31_32/inc/Conditionals_post.h | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- ...ersistent_store_api.cpp => eeprom_api.cpp} | 2 +- .../{persistent_store_api.h => eeprom_api.h} | 0 Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 11 +- .../screens/interface_settings_screen.cpp | 2 +- Marlin/src/module/configuration_store.cpp | 2 +- Marlin/src/module/configuration_store.h | 2 +- Marlin/src/module/printcounter.cpp | 2 +- Marlin/src/module/printcounter.h | 4 +- Marlin/src/pins/samd/pins_RAMPS_144.h | 3 +- platformio.ini | 1 + 41 files changed, 413 insertions(+), 179 deletions(-) rename Marlin/src/HAL/AVR/{persistent_store_eeprom.cpp => eeprom.cpp} (97%) rename Marlin/src/HAL/DUE/{persistent_store_eeprom.cpp => eeprom.cpp} (98%) rename Marlin/src/HAL/ESP32/{persistent_store_impl.cpp => eeprom_impl.cpp} (97%) rename Marlin/src/HAL/LINUX/{persistent_store_impl.cpp => eeprom_impl.cpp} (98%) rename Marlin/src/HAL/LPC1768/{persistent_store_api.h => eeprom_api.h} (95%) rename Marlin/src/HAL/LPC1768/{persistent_store_flash.cpp => eeprom_flash.cpp} (99%) rename Marlin/src/HAL/LPC1768/{persistent_store_sdcard.cpp => eeprom_sdcard.cpp} (99%) create mode 100644 Marlin/src/HAL/SAMD51/QSPIFlash.cpp create mode 100644 Marlin/src/HAL/SAMD51/QSPIFlash.h create mode 100644 Marlin/src/HAL/SAMD51/eeprom.cpp create mode 100644 Marlin/src/HAL/SAMD51/eeprom_flash.cpp create mode 100644 Marlin/src/HAL/SAMD51/eeprom_qspi.cpp delete mode 100644 Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp rename Marlin/src/HAL/STM32/{persistent_store_flash.cpp => eeprom_flash.cpp} (99%) rename Marlin/src/HAL/STM32/{persistent_store_impl.cpp => eeprom_impl.cpp} (91%) rename Marlin/src/HAL/STM32/{persistent_store_sdcard.cpp => eeprom_sdcard.cpp} (98%) rename Marlin/src/HAL/STM32F1/{persistent_store_eeprom.cpp => eeprom.cpp} (95%) rename Marlin/src/HAL/STM32F1/{persistent_store_flash.cpp => eeprom_flash.cpp} (95%) rename Marlin/src/HAL/STM32F1/{persistent_store_sdcard.cpp => eeprom_sdcard.cpp} (98%) rename Marlin/src/HAL/STM32_F4_F7/{persistent_store_eeprom.cpp => eeprom.cpp} (98%) rename Marlin/src/HAL/TEENSY31_32/{persistent_store_impl.cpp => eeprom_impl.cpp} (97%) rename Marlin/src/HAL/TEENSY35_36/{persistent_store_eeprom.cpp => eeprom.cpp} (98%) rename Marlin/src/HAL/shared/{persistent_store_api.cpp => eeprom_api.cpp} (96%) rename Marlin/src/HAL/shared/{persistent_store_api.h => eeprom_api.h} (100%) diff --git a/Marlin/src/HAL/AVR/persistent_store_eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp similarity index 97% rename from Marlin/src/HAL/AVR/persistent_store_eeprom.cpp rename to Marlin/src/HAL/AVR/eeprom.cpp index 1ae37f892a..ee416b7a12 100644 --- a/Marlin/src/HAL/AVR/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -25,7 +25,7 @@ #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/DUE/EepromEmulation.cpp b/Marlin/src/HAL/DUE/EepromEmulation.cpp index f1ae224bfc..66af50cfd2 100644 --- a/Marlin/src/HAL/DUE/EepromEmulation.cpp +++ b/Marlin/src/HAL/DUE/EepromEmulation.cpp @@ -57,7 +57,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/Marduino.h" -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #define EEPROMSize 4096 #define PagesPerGroup 128 diff --git a/Marlin/src/HAL/DUE/persistent_store_eeprom.cpp b/Marlin/src/HAL/DUE/eeprom.cpp similarity index 98% rename from Marlin/src/HAL/DUE/persistent_store_eeprom.cpp rename to Marlin/src/HAL/DUE/eeprom.cpp index fbdc760e45..ec9ef51ffc 100644 --- a/Marlin/src/HAL/DUE/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/DUE/eeprom.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) #include "../../inc/MarlinConfig.h" -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION) #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h index b52462f6d8..8a305009ce 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -21,7 +21,7 @@ */ #pragma once -#if USE_EMULATED_EEPROM +#if USE_FALLBACK_EEPROM #undef SRAM_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/ESP32/persistent_store_impl.cpp b/Marlin/src/HAL/ESP32/eeprom_impl.cpp similarity index 97% rename from Marlin/src/HAL/ESP32/persistent_store_impl.cpp rename to Marlin/src/HAL/ESP32/eeprom_impl.cpp index 7113b68412..dbfee14055 100644 --- a/Marlin/src/HAL/ESP32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/ESP32/eeprom_impl.cpp @@ -26,7 +26,7 @@ #if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include "EEPROM.h" #define EEPROM_SIZE 4096 diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h index e51b55698e..11603c9ef4 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/LINUX/persistent_store_impl.cpp b/Marlin/src/HAL/LINUX/eeprom_impl.cpp similarity index 98% rename from Marlin/src/HAL/LINUX/persistent_store_impl.cpp rename to Marlin/src/HAL/LINUX/eeprom_impl.cpp index 660ecd56f1..4745f05673 100644 --- a/Marlin/src/HAL/LINUX/persistent_store_impl.cpp +++ b/Marlin/src/HAL/LINUX/eeprom_impl.cpp @@ -26,7 +26,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include #define LINUX_EEPROM_SIZE (E2END + 1) diff --git a/Marlin/src/HAL/LPC1768/persistent_store_api.h b/Marlin/src/HAL/LPC1768/eeprom_api.h similarity index 95% rename from Marlin/src/HAL/LPC1768/persistent_store_api.h rename to Marlin/src/HAL/LPC1768/eeprom_api.h index 55a58fde1d..f874eac58a 100644 --- a/Marlin/src/HAL/LPC1768/persistent_store_api.h +++ b/Marlin/src/HAL/LPC1768/eeprom_api.h @@ -21,6 +21,6 @@ */ #pragma once -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/LPC1768/persistent_store_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp similarity index 99% rename from Marlin/src/HAL/LPC1768/persistent_store_flash.cpp rename to Marlin/src/HAL/LPC1768/eeprom_flash.cpp index e166858d64..9225807480 100644 --- a/Marlin/src/HAL/LPC1768/persistent_store_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp @@ -40,7 +40,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) -#include "persistent_store_api.h" +#include "eeprom_api.h" extern "C" { #include diff --git a/Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp similarity index 99% rename from Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp rename to Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index aa61938b02..d982bd6268 100644 --- a/Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -26,7 +26,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "persistent_store_api.h" +#include "eeprom_api.h" #include #include diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index a8d102e865..490cfd50e8 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -21,6 +21,6 @@ */ #pragma once -#if USE_EMULATED_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp new file mode 100644 index 0000000000..76a3329707 --- /dev/null +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp @@ -0,0 +1,78 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(QSPI_EEPROM) + +#include "QSPIFlash.h" + +#define INVALID_ADDR 0xffffffff +#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1)) +#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1)) + +Adafruit_SPIFlashBase * QSPIFlash::_flashBase = nullptr; +uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE]; +uint32_t QSPIFlash::_addr = INVALID_ADDR; + +void QSPIFlash::begin() { + if (_flashBase != nullptr) return; + + _flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI()); + _flashBase->begin(NULL); +} + +size_t QSPIFlash::size() { + return _flashBase->size(); +} + +uint8_t QSPIFlash::readByte(const uint32_t address) { + if (SECTOR_OF(address) == _addr) return _buf[OFFSET_OF(address)]; + + return _flashBase->read8(address); +} + +void QSPIFlash::writeByte(const uint32_t address, const uint8_t value) { + uint32_t const sector_addr = SECTOR_OF(address); + + // Page changes, flush old and update new cache + if (sector_addr != _addr) { + flush(); + _addr = sector_addr; + + // read a whole page from flash + _flashBase->readBuffer(sector_addr, _buf, SFLASH_SECTOR_SIZE); + } + + _buf[OFFSET_OF(address)] = value; +} + +void QSPIFlash::flush() { + if (_addr == INVALID_ADDR) return; + + _flashBase->eraseSector(_addr / SFLASH_SECTOR_SIZE); + _flashBase->writeBuffer(_addr, _buf, SFLASH_SECTOR_SIZE); + + _addr = INVALID_ADDR; +} + +#endif // QSPI_EEPROM diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h new file mode 100644 index 0000000000..7f75286ebf --- /dev/null +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h @@ -0,0 +1,51 @@ +/** + * @file QSPIFlash.h + * + * The MIT License (MIT) + * + * Copyright (c) 2019 Ha Thach and Dean Miller for Adafruit Industries LLC + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * Derived from Adafruit_SPIFlash class with no SdFat references + * + */ + +#pragma once + +#include "Adafruit_SPIFlashBase.h" + +// This class extends Adafruit_SPIFlashBase by adding caching support. +// +// This class will use 4096 Bytes of RAM as a block cache. +class QSPIFlash { + public: + static void begin(); + static size_t size(); + static uint8_t readByte(const uint32_t address); + static void writeByte(const uint32_t address, const uint8_t v); + static void flush(); + + private: + static Adafruit_SPIFlashBase * _flashBase; + static uint8_t _buf[SFLASH_SECTOR_SIZE]; + static uint32_t _addr; +}; + +extern QSPIFlash qspi; diff --git a/Marlin/src/HAL/SAMD51/eeprom.cpp b/Marlin/src/HAL/SAMD51/eeprom.cpp new file mode 100644 index 0000000000..e167515bff --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom.cpp @@ -0,0 +1,66 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __SAMD51__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(EEPROM_SETTINGS) && NONE(QSPI_EEPROM, FLASH_EEPROM_EMULATION) + +#include "../shared/eeprom_api.h" + +size_t PersistentStore::capacity() { return E2END + 1; } + +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + uint8_t c = eeprom_read_byte((uint8_t*)pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // EEPROM_SETTINGS && !(QSPI_EEPROM || FLASH_EEPROM_EMULATION) +#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp new file mode 100644 index 0000000000..fd8973369a --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp @@ -0,0 +1,96 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __SAMD51__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(FLASH_EEPROM_EMULATION) + +#include "../shared/eeprom_api.h" + +#define NVMCTRL_CMD(c) do{ \ + SYNC(!NVMCTRL->STATUS.bit.READY); \ + NVMCTRL->INTFLAG.bit.DONE = true; \ + NVMCTRL->CTRLB.reg = c | NVMCTRL_CTRLB_CMDEX_KEY; \ + SYNC(NVMCTRL->INTFLAG.bit.DONE); \ + }while(0) +#define NVMCTRL_FLUSH() do{ \ + if (NVMCTRL->SEESTAT.bit.LOAD) \ + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_SEEFLUSH); \ + }while(0) + +size_t PersistentStore::capacity() { + const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, + sblk = NVMCTRL->SEESTAT.bit.SBLK; + + return (!psz && !sblk) ? 0 + : (psz <= 2) ? (0x200 << psz) + : (sblk == 1 || psz == 3) ? 4096 + : (sblk == 2 || psz == 4) ? 8192 + : (sblk <= 4 || psz == 5) ? 16384 + : (sblk >= 9 && psz == 7) ? 65536 + : 32768; +} + +bool PersistentStore::access_start() { + NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active + if (NVMCTRL->SEESTAT.bit.RLOCK) + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access + return true; +} + +bool PersistentStore::access_finish() { + NVMCTRL_FLUSH(); + if (!NVMCTRL->SEESTAT.bit.LOCK) + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + SYNC(NVMCTRL->SEESTAT.bit.BUSY); + if (NVMCTRL->INTFLAG.bit.SEESFULL) + NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer' + ((volatile uint8_t *)SEEPROM_ADDR)[pos] = v; + SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC); + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + SYNC(NVMCTRL->SEESTAT.bit.BUSY); + uint8_t c = ((volatile uint8_t *)SEEPROM_ADDR)[pos]; + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // FLASH_EEPROM_EMULATION +#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp new file mode 100644 index 0000000000..c6aa383f9f --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp @@ -0,0 +1,71 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef __SAMD51__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(QSPI_EEPROM) + +#include "../shared/eeprom_api.h" + +#include "QSPIFlash.h" + +static bool initialized; + +size_t PersistentStore::capacity() { return qspi.size(); } + +bool PersistentStore::access_start() { + if (!initialized) { + qspi.begin(); + initialized = true; + } + return true; +} + +bool PersistentStore::access_finish() { + qspi.flush(); + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + qspi.writeByte(pos, v); + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + uint8_t c = qspi.readByte(pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // QSPI_EEPROM +#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index b52462f6d8..490cfd50e8 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -21,8 +21,6 @@ */ #pragma once -#if USE_EMULATED_EEPROM - #undef SRAM_EEPROM_EMULATION - #undef SDCARD_EEPROM_EMULATION +#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp b/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp deleted file mode 100644 index 6b7326bb25..0000000000 --- a/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -#ifdef __SAMD51__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(EEPROM_SETTINGS) - -#include "../shared/persistent_store_api.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - #define NVMCTRL_CMD(c) do{ \ - SYNC(!NVMCTRL->STATUS.bit.READY); \ - NVMCTRL->INTFLAG.bit.DONE = true; \ - NVMCTRL->CTRLB.reg = c | NVMCTRL_CTRLB_CMDEX_KEY; \ - SYNC(NVMCTRL->INTFLAG.bit.DONE); \ - }while(0) - #define NVMCTRL_FLUSH() do{ \ - if (NVMCTRL->SEESTAT.bit.LOAD) \ - NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_SEEFLUSH); \ - }while(0) -#endif - -bool PersistentStore::access_start() { - #if ENABLED(FLASH_EEPROM_EMULATION) - NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active - #endif - - return true; -} - -bool PersistentStore::access_finish() { - #if ENABLED(FLASH_EEPROM_EMULATION) - NVMCTRL_FLUSH(); - if (!NVMCTRL->SEESTAT.bit.LOCK) - NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access - #endif - - return true; -} - -bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { - #if ENABLED(FLASH_EEPROM_EMULATION) - if (NVMCTRL->SEESTAT.bit.RLOCK) - NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access - #endif - - while (size--) { - const uint8_t v = *value; - #if ENABLED(FLASH_EEPROM_EMULATION) - SYNC(NVMCTRL->SEESTAT.bit.BUSY); - if (NVMCTRL->INTFLAG.bit.SEESFULL) - NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer' - ((volatile uint8_t *)SEEPROM_ADDR)[pos] = v; - SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC); - #else - uint8_t * const p = (uint8_t * const)pos; - if (v != eeprom_read_byte(p)) { - eeprom_write_byte(p, v); - delay(2); - if (eeprom_read_byte(p) != v) { - SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); - return true; - } - } - #endif - crc16(crc, &v, 1); - pos++; - value++; - } - return false; -} - -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { - while (size--) { - uint8_t c; - #if ENABLED(FLASH_EEPROM_EMULATION) - SYNC(NVMCTRL->SEESTAT.bit.BUSY); - c = ((volatile uint8_t *)SEEPROM_ADDR)[pos]; - #else - c = eeprom_read_byte((uint8_t*)pos); - #endif - if (writing) *value = c; - crc16(crc, &c, 1); - pos++; - value++; - } - return false; -} - -size_t PersistentStore::capacity() { - #if ENABLED(FLASH_EEPROM_EMULATION) - const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, - sblk = NVMCTRL->SEESTAT.bit.SBLK; - - if (!psz && !sblk) return 0; - else if (psz <= 2) return (0x200 << psz); - else if (sblk == 1 || psz == 3) return 4096; - else if (sblk == 2 || psz == 4) return 8192; - else if (sblk <= 4 || psz == 5) return 16384; - else if (sblk >= 9 && psz == 7) return 65536; - else return 32768; - #else - return E2END + 1; - #endif -} - -#endif // EEPROM_SETTINGS - -#endif // __SAMD51__ diff --git a/Marlin/src/HAL/STM32/persistent_store_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp similarity index 99% rename from Marlin/src/HAL/STM32/persistent_store_flash.cpp rename to Marlin/src/HAL/STM32/eeprom_flash.cpp index 80ef901ceb..39012f8205 100644 --- a/Marlin/src/HAL/STM32/persistent_store_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -27,7 +27,7 @@ #if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" // Only STM32F4 can support wear leveling at this time diff --git a/Marlin/src/HAL/STM32/persistent_store_impl.cpp b/Marlin/src/HAL/STM32/eeprom_impl.cpp similarity index 91% rename from Marlin/src/HAL/STM32/persistent_store_impl.cpp rename to Marlin/src/HAL/STM32/eeprom_impl.cpp index d9538741dd..cd0f93e8d8 100644 --- a/Marlin/src/HAL/STM32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/STM32/eeprom_impl.cpp @@ -24,9 +24,9 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(USE_REAL_EEPROM, SRAM_EEPROM_EMULATION) +#if EITHER(USE_WIRED_EEPROM, SRAM_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; @@ -41,7 +41,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint8_t v = *value; // Save to either external EEPROM, program flash or Backup SRAM - #if USE_REAL_EEPROM + #if USE_WIRED_EEPROM // EEPROM has only ~100,000 write cycles, // so only write bytes that have changed! uint8_t * const p = (uint8_t * const)pos; @@ -68,7 +68,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t do { // Read from either external EEPROM, program flash or Backup SRAM const uint8_t c = ( - #if USE_REAL_EEPROM + #if USE_WIRED_EEPROM eeprom_read_byte((uint8_t*)pos) #else (*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos))) @@ -85,7 +85,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return ( - #if USE_REAL_EEPROM + #if USE_WIRED_EEPROM E2END + 1 #else 4096 // 4kB @@ -93,5 +93,5 @@ size_t PersistentStore::capacity() { ); } -#endif // USE_REAL_EEPROM || SRAM_EEPROM_EMULATION +#endif // USE_WIRED_EEPROM || SRAM_EEPROM_EMULATION #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/persistent_store_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp similarity index 98% rename from Marlin/src/HAL/STM32/persistent_store_sdcard.cpp rename to Marlin/src/HAL/STM32/eeprom_sdcard.cpp index c5afc557e9..2b89c21b89 100644 --- a/Marlin/src/HAL/STM32/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -30,7 +30,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #ifndef E2END #define E2END 0xFFF // 4KB diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index e51b55698e..11603c9ef4 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp b/Marlin/src/HAL/STM32F1/eeprom.cpp similarity index 95% rename from Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp rename to Marlin/src/HAL/STM32F1/eeprom.cpp index 1b3714c56d..ed5d50cbde 100644 --- a/Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom.cpp @@ -22,9 +22,9 @@ #include "../../inc/MarlinConfig.h" -#if USE_REAL_EEPROM +#if USE_WIRED_EEPROM -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { #if ENABLED(SPI_EEPROM) @@ -73,5 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return E2END + 1; } -#endif // USE_REAL_EEPROM +#endif // USE_WIRED_EEPROM #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/persistent_store_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp similarity index 95% rename from Marlin/src/HAL/STM32F1/persistent_store_flash.cpp rename to Marlin/src/HAL/STM32F1/eeprom_flash.cpp index 3d6a3b4591..9c81730465 100644 --- a/Marlin/src/HAL/STM32F1/persistent_store_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp @@ -31,10 +31,9 @@ #include "../../inc/MarlinConfig.h" -// This is for EEPROM emulation in flash -#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION) +#if ENABLED(FLASH_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include #include @@ -108,5 +107,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return EEPROM_SIZE; } -#endif // EEPROM_SETTINGS && EEPROM FLASH +#endif // FLASH_EEPROM_EMULATION #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp similarity index 98% rename from Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp rename to Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp index 8b5d89ad83..7894e69787 100644 --- a/Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp @@ -31,7 +31,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #ifndef E2END #define E2END 0xFFF // 4KB @@ -101,5 +101,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } #endif // SDCARD_EEPROM_EMULATION - #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp similarity index 98% rename from Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp rename to Marlin/src/HAL/STM32_F4_F7/eeprom.cpp index 2ffbc609ec..b957aae6a8 100644 --- a/Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h index 5a190342ac..d21624955e 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h @@ -22,7 +22,7 @@ #pragma once #if ENABLED(EEPROM_SETTINGS) && defined(STM32F7) - #undef USE_REAL_EEPROM + #undef USE_WIRED_EEPROM #undef SRAM_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp similarity index 97% rename from Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp rename to Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp index 6a179cd962..96499d4f19 100644 --- a/Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp @@ -22,7 +22,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h index e51b55698e..11603c9ef4 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp similarity index 98% rename from Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp rename to Marlin/src/HAL/TEENSY35_36/eeprom.cpp index 32b215ee6e..c66a45e2a5 100644 --- a/Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include bool PersistentStore::access_start() { return true; } diff --git a/Marlin/src/HAL/shared/persistent_store_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp similarity index 96% rename from Marlin/src/HAL/shared/persistent_store_api.cpp rename to Marlin/src/HAL/shared/eeprom_api.cpp index 735fa4278b..d8839e3d9d 100644 --- a/Marlin/src/HAL/shared/persistent_store_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.cpp @@ -24,7 +24,7 @@ #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) - #include "persistent_store_api.h" + #include "eeprom_api.h" PersistentStore persistentStore; #endif diff --git a/Marlin/src/HAL/shared/persistent_store_api.h b/Marlin/src/HAL/shared/eeprom_api.h similarity index 100% rename from Marlin/src/HAL/shared/persistent_store_api.h rename to Marlin/src/HAL/shared/eeprom_api.h diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 1ac036e5bc..217d894543 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -27,7 +27,7 @@ #include "../bedlevel.h" #include "../../../MarlinCore.h" - #include "../../../HAL/shared/persistent_store_api.h" + #include "../../../HAL/shared/eeprom_api.h" #include "../../../libs/hex_print_routines.h" #include "../../../module/configuration_store.h" #include "../../../lcd/ultralcd.h" diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ebc77b9383..d9db986466 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -35,16 +35,19 @@ #define HAS_LINEAR_E_JERK 1 #endif -// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation +// Determine which type of 'EEPROM' is in use #if ENABLED(EEPROM_SETTINGS) - #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && EITHER(I2C_EEPROM, SPI_EEPROM) - #define USE_REAL_EEPROM 1 + // EEPROM type may be defined by compile flags, configs, HALs, or pins + // Set additional flags to let HALs choose in their Conditionals_post.h + #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM) + #define USE_WIRED_EEPROM 1 #else - #define USE_EMULATED_EEPROM 1 + #define USE_FALLBACK_EEPROM 1 #endif #else #undef I2C_EEPROM #undef SPI_EEPROM + #undef QSPI_EEPROM #undef SDCARD_EEPROM_EMULATION #undef SRAM_EEPROM_EMULATION #undef FLASH_EEPROM_EMULATION diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 61875c52f1..3de03579e4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -252,7 +252,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { } #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - #include "../../../../../HAL/shared/persistent_store_api.h" + #include "../../../../../HAL/shared/eeprom_api.h" bool restoreEEPROM() { uint8_t data[ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE]; diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 129e207d29..d80fe50195 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -57,7 +57,7 @@ #include "../MarlinCore.h" #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) - #include "../HAL/shared/persistent_store_api.h" + #include "../HAL/shared/eeprom_api.h" #endif #include "probe.h" diff --git a/Marlin/src/module/configuration_store.h b/Marlin/src/module/configuration_store.h index a2c8d97dfa..f2e84c9664 100644 --- a/Marlin/src/module/configuration_store.h +++ b/Marlin/src/module/configuration_store.h @@ -24,7 +24,7 @@ #include "../inc/MarlinConfig.h" #if ENABLED(EEPROM_SETTINGS) - #include "../HAL/shared/persistent_store_api.h" + #include "../HAL/shared/eeprom_api.h" #endif class MarlinSettings { diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 4b4d4b60ad..3623c88a13 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -35,7 +35,7 @@ Stopwatch print_job_timer; // Global Print Job Timer instance #include "printcounter.h" #include "../MarlinCore.h" -#include "../HAL/shared/persistent_store_api.h" +#include "../HAL/shared/eeprom_api.h" #if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0 #include "../libs/buzzer.h" diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 261cdf058b..39a237cc44 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -28,7 +28,7 @@ // Print debug messages with M111 S2 //#define DEBUG_PRINTCOUNTER -#if USE_REAL_EEPROM +#if USE_WIRED_EEPROM // round up address to next page boundary (assuming 32 byte pages) #define STATS_EEPROM_ADDRESS 0x40 #else @@ -57,7 +57,7 @@ class PrintCounter: public Stopwatch { private: typedef Stopwatch super; - #if USE_REAL_EEPROM || defined(CPU_32_BIT) + #if USE_WIRED_EEPROM || defined(CPU_32_BIT) typedef uint32_t eeprom_address_t; #else typedef uint16_t eeprom_address_t; diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index b7d5172e0d..f02a8b86bd 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -44,8 +44,9 @@ // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) +//#define QSPI_EEPROM // Use AGCM4 onboard QSPI EEPROM (Uses 4K of RAM) #define I2C_EEPROM // EEPROM on I2C-0 +#define E2END 0x7FFF // 32K (24lc256) // // Limit Switches diff --git a/platformio.ini b/platformio.ini index 2f3e86c316..13808d299a 100644 --- a/platformio.ini +++ b/platformio.ini @@ -792,6 +792,7 @@ build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + Adafruit_SPIFlash=https://github.com/adafruit/Adafruit_SPIFlash/archive/master.zip debug_tool = jlink # From bed41af868f352bc0ca72b0b6936a97420c64ecf Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Fri, 27 Mar 2020 18:30:17 -0400 Subject: [PATCH 0059/1454] Fix Stepper PWM menu (#17298) --- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 1577e59fc1..f2327b75e5 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -84,7 +84,7 @@ void menu_cancelobject(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_CURRENT_PWM(LABEL,I) EDIT_ITEM_P(long5, PSTR(LABEL), &stepper.motor_current_setting[I], 100, 2000, stepper.refresh_motor_power) - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y) EDIT_CURRENT_PWM(STR_X STR_Y, 0); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) From 8752fbd92c8edcd777b6a2afe54f4d70d3fc4d85 Mon Sep 17 00:00:00 2001 From: Mathias Rasmussen Date: Fri, 27 Mar 2020 23:38:28 +0100 Subject: [PATCH 0060/1454] Store case light brightness in EEPROM (#17307) --- Marlin/src/module/configuration_store.cpp | 39 +++++++++++++++++++++++ 1 file changed, 39 insertions(+) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index d80fe50195..2ecc9299c9 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -127,6 +127,11 @@ void M710_report(const bool forReplay); #endif +#define HAS_CASE_LIGHT_BRIGHTNESS (ENABLED(CASE_LIGHT_MENU) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS)) +#if HAS_CASE_LIGHT_BRIGHTNESS + #include "../feature/caselight.h" +#endif + #pragma pack(push, 1) // No padding between variables typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t; @@ -376,6 +381,13 @@ typedef struct SettingsDataStruct { uint8_t extui_data[ExtUI::eeprom_data_size]; #endif + // + // HAS_CASE_LIGHT_BRIGHTNESS + // + #if HAS_CASE_LIGHT_BRIGHTNESS + uint8_t case_light_brightness; + #endif + } SettingsData; //static_assert(sizeof(SettingsData) <= E2END + 1, "EEPROM too small to contain SettingsData!"); @@ -441,6 +453,10 @@ void MarlinSettings::postprocess() { planner.recalculate_max_e_jerk(); #endif + #if HAS_CASE_LIGHT_BRIGHTNESS + update_case_light(); + #endif + // Refresh steps_to_mm with the reciprocal of axis_steps_per_mm // and init stepper.count[], planner.position[] with current_position planner.refresh_positioning(); @@ -1309,6 +1325,13 @@ void MarlinSettings::postprocess() { } #endif + // + // Case Light Brightness + // + #if HAS_CASE_LIGHT_BRIGHTNESS + EEPROM_WRITE(case_light_brightness); + #endif + // // Validate CRC and Data Size // @@ -2163,6 +2186,14 @@ void MarlinSettings::postprocess() { } #endif + // + // Case Light Brightness + // + #if HAS_CASE_LIGHT_BRIGHTNESS + _FIELD_TEST(case_light_brightness); + EEPROM_READ(case_light_brightness); + #endif + eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET)); if (eeprom_error) { DEBUG_ECHO_START(); @@ -2458,6 +2489,14 @@ void MarlinSettings::reset() { ExtUI::onFactoryReset(); #endif + // + // Case Light Brightness + // + + #if HAS_CASE_LIGHT_BRIGHTNESS + case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS; + #endif + // // Magnetic Parking Extruder // From e71b25a555e869338723fa17799bcb9d4ea44fbe Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 28 Mar 2020 00:03:16 +0000 Subject: [PATCH 0061/1454] [cron] Bump distribution date (2020-03-28) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index afbb5cf3c8..9978e3e6d3 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-27" + #define STRING_DISTRIBUTION_DATE "2020-03-28" #endif /** From de648bfdc1de5b3b3bb93e39d4337c3f9bff1211 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Fri, 27 Mar 2020 22:08:47 -0400 Subject: [PATCH 0062/1454] Add Funmat HT V4.0 board support (#17305) Co-authored-by: Scott Lahteine --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/mega/pins_INTAMSYS40.h | 152 +++++++++++++++++++++++ Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 16 +-- 4 files changed, 163 insertions(+), 8 deletions(-) create mode 100644 Marlin/src/pins/mega/pins_INTAMSYS40.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 86107f7d86..30c2d3eb87 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -144,6 +144,7 @@ #define BOARD_LEAPFROG_XEED2015 1321 // Leapfrog Xeed 2015 #define BOARD_PICA_REVB 1322 // PICA Shield (original version) #define BOARD_PICA 1323 // PICA Shield (rev C or later) +#define BOARD_INTAMSYS40 1324 // Intamsys 4.0 (Funmat HT) // // ATmega1281, ATmega2561 diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h new file mode 100644 index 0000000000..c688823ddf --- /dev/null +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -0,0 +1,152 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Intamsys Funmat HT V4.0 Mainboard + * 4988 Drivers Tested + * 2208 version exists and may or may not work + */ + +#ifndef __AVR_ATmega2560__ + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" +#endif + +#define BOARD_INFO_NAME "Intamsys 4.0" + +// +// Servos +// +#define SERVO0_PIN 12 // Uses High Temp Present Jumper Pin + +// +// Limit Switches +// +#define X_STOP_PIN 22 +#define Y_STOP_PIN 26 +#define Z_MIN_PIN 29 +#define Z_MAX_PIN 69 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 69 +#endif + +#define FIL_RUNOUT_PIN 10 + +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 // 44 + +#define Y_STEP_PIN 32 // 33 +#define Y_DIR_PIN 33 // 31, 32 +#define Y_ENABLE_PIN 31 // 32 + +#define Z_STEP_PIN 35 // 35 +#define Z_DIR_PIN 36 +#define Z_ENABLE_PIN 34 // 34 + +#define E0_STEP_PIN 42 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 37 + +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 + +#define MOTOR_CURRENT_PWM_X_PIN 11 +#define MOTOR_CURRENT_PWM_Y_PIN 44 +#define MOTOR_CURRENT_PWM_Z_PIN 45 +#define MOTOR_CURRENT_PWM_E_PIN 46 + +// Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range +#ifndef MOTOR_CURRENT_PWM_RANGE + #define MOTOR_CURRENT_PWM_RANGE 2000 +#endif +#define DEFAULT_PWM_MOTOR_CURRENT { 1300, 1300, 1250 } + +// +// Temperature Sensors +// +#define TEMP_0_PIN 8 // Analog Input D62 +#define TEMP_BED_PIN 10 // Analog Input D64 + +#define TEMP_CHAMBER_PIN 9 // Analog Input D63 + +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 // PWM +#define HEATER_BED_PIN 4 // PWM +#define HEATER_CHAMBER_PIN 3 // PWM +#define FAN_PIN 7 // PWM + +// +// Misc. Functions +// +#define SDSS 53 +#define SD_DETECT_PIN 39 + +#if ENABLED(CASE_LIGHT_ENABLE) + #define CASE_LIGHT_PIN 8 +#endif + +#if ENABLED(PSU_CONTROL) + #define PS_ON_PIN 38 // UPS Module +#endif + +// +// LCD Controller +// + +#define BEEPER_PIN 18 + +#if HAS_SPI_LCD + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 30 + #define LCD_PINS_D4 14 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 + #define BTN_EN1 40 + #define BTN_EN2 41 + #define BTN_ENC 19 +#endif + +///////////////////// SPARE HEADERS ////////////// + +/** + * + * J25 + * 1 D54 + * 2 D55 + * 3 D56 + * 4 D57 + * 5 D58 + * 6 D59 + * 7 D60 + * 8 D61 + +Hotend High Temp Connected : D12 +*/ diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b43ba1cbc6..5de75a1f0e 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -258,6 +258,8 @@ #include "mega/pins_PICA.h" // ATmega2560 env:mega2560 #elif MB(PICA_REVB) #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 +#elif MB(INTAMSYS40) + #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 2f2881ee3f..a8c6d30eb4 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -178,14 +178,14 @@ //#define E4_HARDWARE_SERIAL Serial1 // Unused servo pins may be repurposed with SoftwareSerialM - //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN - //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN - //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN - //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN - //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN - //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN - //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - //#define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN + //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN + //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN + //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN + //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + //#define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate for software serial reliability #if HAS_TMC_SW_SERIAL From 53fe572bbdfe4d51e420f6d002197cee533e17fd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 27 Mar 2020 22:00:27 -0500 Subject: [PATCH 0063/1454] Limited backlash editing with Core kinematics (#17281) --- Marlin/src/gcode/calibrate/G28.cpp | 20 ++-- Marlin/src/gcode/calibrate/G425.cpp | 144 +++++++++++++++----------- Marlin/src/gcode/calibrate/M425.cpp | 6 +- Marlin/src/inc/Conditionals_post.h | 13 +++ Marlin/src/inc/MarlinConfig.h | 3 +- Marlin/src/lcd/menu/menu_backlash.cpp | 6 +- 6 files changed, 114 insertions(+), 78 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 4603c76967..fafce9a896 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -255,28 +255,28 @@ void GcodeSuite::G28() { #define HAS_HOMING_CURRENT (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2)) #if HAS_HOMING_CURRENT - auto debug_current = [](const char * const s, const int16_t a, const int16_t b){ - DEBUG_ECHO(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); + auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){ + serialprintPGM(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); }; #if HAS_CURRENT_HOME(X) const int16_t tmc_save_current_X = stepperX.getMilliamps(); stepperX.rms_current(X_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("X", tmc_save_current_X, X_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("X"), tmc_save_current_X, X_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(X2) const int16_t tmc_save_current_X2 = stepperX2.getMilliamps(); stepperX2.rms_current(X2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("X2", tmc_save_current_X2, X2_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("X2"), tmc_save_current_X2, X2_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Y) const int16_t tmc_save_current_Y = stepperY.getMilliamps(); stepperY.rms_current(Y_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("Y", tmc_save_current_Y, Y_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("Y"), tmc_save_current_Y, Y_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Y2) const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps(); stepperY2.rms_current(Y2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("Y2", tmc_save_current_Y2, Y2_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); #endif #endif @@ -345,12 +345,8 @@ void GcodeSuite::G28() { #endif // Home Y (before X) - #if ENABLED(HOME_Y_BEFORE_X) - - if (doY || (doX && ENABLED(CODEPENDENT_XY_HOMING))) - homeaxis(Y_AXIS); - - #endif + if (ENABLED(HOME_Y_BEFORE_X) && (doY || (ENABLED(CODEPENDENT_XY_HOMING) && doX))) + homeaxis(Y_AXIS); // Home X if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) { diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 69fb29165d..42c56fe51d 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -37,6 +37,21 @@ #include "../../module/endstops.h" #include "../../feature/bedlevel/bedlevel.h" +#if !AXIS_CAN_CALIBRATE(X) + #undef CALIBRATION_MEASURE_LEFT + #undef CALIBRATION_MEASURE_RIGHT +#endif + +#if !AXIS_CAN_CALIBRATE(Y) + #undef CALIBRATION_MEASURE_FRONT + #undef CALIBRATION_MEASURE_BACK +#endif + +#if !AXIS_CAN_CALIBRATE(Z) + #undef CALIBRATION_MEASURE_AT_TOP_EDGES +#endif + + /** * G425 backs away from the calibration object by various distances * depending on the confidence level: @@ -207,42 +222,52 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state, inline void probe_side(measurements_t &m, const float uncertainty, const side_t side, const bool probe_top_at_edge=false) { const xyz_float_t dimensions = CALIBRATION_OBJECT_DIMENSIONS; AxisEnum axis; - float dir; + float dir = 1; park_above_object(m, uncertainty); switch (side) { - case TOP: { - const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); - m.obj_center.z = measurement - dimensions.z / 2; - m.obj_side[TOP] = measurement; - return; - } - case RIGHT: axis = X_AXIS; dir = -1; break; - case FRONT: axis = Y_AXIS; dir = 1; break; - case LEFT: axis = X_AXIS; dir = 1; break; - case BACK: axis = Y_AXIS; dir = -1; break; + #if AXIS_CAN_CALIBRATE(Z) + case TOP: { + const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); + m.obj_center.z = measurement - dimensions.z / 2; + m.obj_side[TOP] = measurement; + return; + } + #endif + #if AXIS_CAN_CALIBRATE(X) + case LEFT: axis = X_AXIS; break; + case RIGHT: axis = X_AXIS; dir = -1; break; + #endif + #if AXIS_CAN_CALIBRATE(Y) + case FRONT: axis = Y_AXIS; break; + case BACK: axis = Y_AXIS; dir = -1; break; + #endif default: return; } if (probe_top_at_edge) { - // Probe top nearest the side we are probing - current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]); - calibration_move(); - m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); - m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2; + #if AXIS_CAN_CALIBRATE(Z) + // Probe top nearest the side we are probing + current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]); + calibration_move(); + m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); + m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2; + #endif } - // Move to safe distance to the side of the calibration object - current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); - calibration_move(); + if (AXIS_CAN_CALIBRATE(X) && axis == X_AXIS || AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS) { + // Move to safe distance to the side of the calibration object + current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); + calibration_move(); - // Plunge below the side of the calibration object and measure - current_position.z = m.obj_side[TOP] - CALIBRATION_NOZZLE_TIP_HEIGHT * 0.7; - calibration_move(); - const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty); - m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2); - m.obj_side[side] = measurement; + // Plunge below the side of the calibration object and measure + current_position.z = m.obj_side[TOP] - (CALIBRATION_NOZZLE_TIP_HEIGHT) * 0.7f; + calibration_move(); + const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty); + m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2); + m.obj_side[side] = measurement; + } } /** @@ -252,7 +277,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t * uncertainty in - How far away from the calibration object to begin probing */ inline void probe_sides(measurements_t &m, const float uncertainty) { - #ifdef CALIBRATION_MEASURE_AT_TOP_EDGES + #if ENABLED(CALIBRATION_MEASURE_AT_TOP_EDGES) constexpr bool probe_top_at_edge = true; #else // Probing at the exact center only works if the center is flat. Probing on a washer @@ -261,18 +286,18 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - #ifdef CALIBRATION_MEASURE_RIGHT + #if ENABLED(CALIBRATION_MEASURE_RIGHT) probe_side(m, uncertainty, RIGHT, probe_top_at_edge); #endif - #ifdef CALIBRATION_MEASURE_FRONT + #if ENABLED(CALIBRATION_MEASURE_FRONT) probe_side(m, uncertainty, FRONT, probe_top_at_edge); #endif - #ifdef CALIBRATION_MEASURE_LEFT + #if ENABLED(CALIBRATION_MEASURE_LEFT) probe_side(m, uncertainty, LEFT, probe_top_at_edge); #endif - #ifdef CALIBRATION_MEASURE_BACK + #if ENABLED(CALIBRATION_MEASURE_BACK) probe_side(m, uncertainty, BACK, probe_top_at_edge); #endif @@ -313,7 +338,9 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); + #if AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); + #endif #if ENABLED(CALIBRATION_MEASURE_LEFT) SERIAL_ECHOLNPAIR(" Left: ", m.obj_side[LEFT]); #endif @@ -343,19 +370,25 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_backlash(const measurements_t &m) { SERIAL_ECHOLNPGM("Backlash:"); - #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]); + #if AXIS_CAN_CALIBRATE(X) + #if ENABLED(CALIBRATION_MEASURE_LEFT) + SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_RIGHT) + SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); + #if AXIS_CAN_CALIBRATE(Y) + #if ENABLED(CALIBRATION_MEASURE_FRONT) + SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_BACK) + SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); + #if AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); - #endif - SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); SERIAL_EOL(); } @@ -369,7 +402,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if HAS_Y_CENTER SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); #endif - SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); SERIAL_EOL(); } @@ -417,6 +450,7 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { probe_sides(m, uncertainty); #if ENABLED(BACKLASH_GCODE) + #if HAS_X_CENTER backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2; #elif ENABLED(CALIBRATION_MEASURE_LEFT) @@ -433,18 +467,18 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { backlash.distance_mm.y = m.backlash[BACK]; #endif - backlash.distance_mm.z = m.backlash[TOP]; + if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]; #endif } #if ENABLED(BACKLASH_GCODE) // Turn on backlash compensation and move in all - // directions to take up any backlash + // allowed directions to take up any backlash { // New scope for TEMPORARY_BACKLASH_CORRECTION TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - const xyz_float_t move = { 3, 3, 3 }; + const xyz_float_t move = { AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 }; current_position += move; calibration_move(); current_position -= move; calibration_move(); } @@ -482,26 +516,18 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const // Adjust the hotend offset #if HAS_HOTEND_OFFSET - #if HAS_X_CENTER - hotend_offset[extruder].x += m.pos_error.x; - #endif - #if HAS_Y_CENTER - hotend_offset[extruder].y += m.pos_error.y; - #endif - hotend_offset[extruder].z += m.pos_error.z; + if (ENABLED(HAS_X_CENTER) && AXIS_CAN_CALIBRATE(X)) hotend_offset[extruder].x += m.pos_error.x; + if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) hotend_offset[extruder].y += m.pos_error.y; + if (AXIS_CAN_CALIBRATE(Z)) hotend_offset[extruder].z += m.pos_error.z; normalize_hotend_offsets(); #endif // Correct for positional error, so the object // is at the known actual spot planner.synchronize(); - #if HAS_X_CENTER - update_measurements(m, X_AXIS); - #endif - #if HAS_Y_CENTER - update_measurements(m, Y_AXIS); - #endif - update_measurements(m, Z_AXIS); + if (ENABLED(HAS_X_CENTER) && AXIS_CAN_CALIBRATE(X)) update_measurements(m, X_AXIS); + if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS); + if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS); sync_plan_position(); } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 41c80daf7c..980152a4b1 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -47,7 +47,7 @@ void GcodeSuite::M425() { bool noArgs = true; LOOP_XYZ(a) { - if (parser.seen(XYZ_CHAR(a))) { + if (CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; @@ -74,7 +74,7 @@ void GcodeSuite::M425() { SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); - LOOP_XYZ(a) { + LOOP_XYZ(a) if (CAN_CALIBRATE(a)) { SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_EOL(); @@ -87,7 +87,7 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_XYZ(a) if (backlash.has_measurement(AxisEnum(a))) { + LOOP_XYZ(a) if (CAN_CALIBRATE(a) && backlash.has_measurement(AxisEnum(a))) { SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); } diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d9db986466..9ea298f02d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -139,6 +139,19 @@ #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) #endif +// Calibration codes only for non-core axes +#if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) + #if IS_CORE + #define X_AXIS_INDEX 0 + #define Y_AXIS_INDEX 1 + #define Z_AXIS_INDEX 2 + #define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX) + #else + #define CAN_CALIBRATE(...) 1 + #endif +#endif +#define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) + /** * No adjustable bed on non-cartesians */ diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index d32506702e..c1655015e0 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -35,11 +35,12 @@ #include "Conditionals_post.h" #include HAL_PATH(../HAL, inc/Conditionals_post.h) +#include "../core/types.h" // Ahead of sanity-checks + #include "SanityCheck.h" #include HAL_PATH(../HAL, inc/SanityCheck.h) // Include all core headers -#include "../core/types.h" #include "../core/language.h" #include "../core/utility.h" #include "../core/serial.h" diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index ad9c51d4cf..720694bfff 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -39,9 +39,9 @@ void menu_backlash() { EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &backlash.correction, all_off, all_on); #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f); - EDIT_BACKLASH_DISTANCE(A); - EDIT_BACKLASH_DISTANCE(B); - EDIT_BACKLASH_DISTANCE(C); + if (AXIS_CAN_CALIBRATE(A)) EDIT_BACKLASH_DISTANCE(A); + if (AXIS_CAN_CALIBRATE(B)) EDIT_BACKLASH_DISTANCE(B); + if (AXIS_CAN_CALIBRATE(C)) EDIT_BACKLASH_DISTANCE(C); #ifdef BACKLASH_SMOOTHING_MM EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f); From a84990961a62e4190cfac10b500ce9c693896e83 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 28 Mar 2020 01:19:43 -0500 Subject: [PATCH 0064/1454] Simplify TWIBus debug --- Marlin/src/feature/twibus.cpp | 56 +++++++++++------------------------ Marlin/src/feature/twibus.h | 7 +++-- 2 files changed, 22 insertions(+), 41 deletions(-) diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 60d78018a2..9dbb1deb4f 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -49,37 +49,27 @@ void TWIBus::address(const uint8_t adr) { addr = adr; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("address"), adr); - #endif + debug(PSTR("address"), adr); } void TWIBus::addbyte(const char c) { if (buffer_s >= COUNT(buffer)) return; buffer[buffer_s++] = c; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addbyte"), c); - #endif + debug(PSTR("addbyte"), c); } void TWIBus::addbytes(char src[], uint8_t bytes) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addbytes"), bytes); - #endif + debug(PSTR("addbytes"), bytes); while (bytes--) addbyte(*src++); } void TWIBus::addstring(char str[]) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addstring"), str); - #endif + debug(PSTR("addstring"), str); while (char c = *str++) addbyte(c); } void TWIBus::send() { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("send"), addr); - #endif + debug(PSTR("send"), addr); Wire.beginTransmission(I2C_ADDRESS(addr)); Wire.write(buffer, buffer_s); @@ -89,21 +79,21 @@ void TWIBus::send() { } // static -void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) { +void TWIBus::echoprefix(uint8_t bytes, const char pref[], uint8_t adr) { SERIAL_ECHO_START(); - serialprintPGM(prefix); + serialprintPGM(pref); SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:"); } // static -void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) { - echoprefix(bytes, prefix, adr); +void TWIBus::echodata(uint8_t bytes, const char pref[], uint8_t adr) { + echoprefix(bytes, pref, adr); while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); SERIAL_EOL(); } -void TWIBus::echobuffer(const char prefix[], uint8_t adr) { - echoprefix(buffer_s, prefix, adr); +void TWIBus::echobuffer(const char pref[], uint8_t adr) { + echoprefix(buffer_s, pref, adr); LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } @@ -111,15 +101,11 @@ void TWIBus::echobuffer(const char prefix[], uint8_t adr) { bool TWIBus::request(const uint8_t bytes) { if (!addr) return false; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("request"), bytes); - #endif + debug(PSTR("request"), bytes); // requestFrom() is a blocking function if (Wire.requestFrom(addr, bytes) == 0) { - #if ENABLED(DEBUG_TWIBUS) - debug("request fail", addr); - #endif + debug("request fail", addr); return false; } @@ -127,9 +113,7 @@ bool TWIBus::request(const uint8_t bytes) { } void TWIBus::relay(const uint8_t bytes) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("relay"), bytes); - #endif + debug(PSTR("relay"), bytes); if (request(bytes)) echodata(bytes, PSTR("i2c-reply"), addr); @@ -141,9 +125,7 @@ uint8_t TWIBus::capture(char *dst, const uint8_t bytes) { while (count < bytes && Wire.available()) dst[count++] = Wire.read(); - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("capture"), count); - #endif + debug(PSTR("capture"), count); return count; } @@ -156,16 +138,12 @@ void TWIBus::flush() { #if I2C_SLAVE_ADDRESS > 0 void TWIBus::receive(uint8_t bytes) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("receive"), bytes); - #endif + debug(PSTR("receive"), bytes); echodata(bytes, PSTR("i2c-receive"), 0); } void TWIBus::reply(char str[]/*=nullptr*/) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("reply"), str); - #endif + debug(PSTR("reply"), str); if (str) { reset(); diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index faf9eb38cf..2c1b20da51 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -223,7 +223,6 @@ class TWIBus { #endif #if ENABLED(DEBUG_TWIBUS) - /** * @brief Prints a debug message * @details Prints a simple debug message "TWIBus::function: value" @@ -233,6 +232,10 @@ class TWIBus { static void debug(const char func[], char c); static void debug(const char func[], char adr[]); static inline void debug(const char func[], uint8_t v) { debug(func, (uint32_t)v); } - + #else + static inline void debug(const char[], uint32_t) {} + static inline void debug(const char[], char) {} + static inline void debug(const char[], char[]) {} + static inline void debug(const char[], uint8_t) {} #endif }; From 747b964295118d425ad41cd7593dae48ccf9f14f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 28 Mar 2020 03:18:53 -0500 Subject: [PATCH 0065/1454] Clean up user-wait, SD completion (#17315) --- Marlin/Configuration_adv.h | 4 + Marlin/src/MarlinCore.cpp | 69 ++++-------- Marlin/src/MarlinCore.h | 2 + Marlin/src/feature/mmu2/mmu2.cpp | 3 +- Marlin/src/feature/pause.cpp | 8 +- Marlin/src/gcode/gcode.cpp | 6 +- Marlin/src/gcode/gcode.h | 4 + Marlin/src/gcode/lcd/M0_M1.cpp | 51 +++------ Marlin/src/gcode/sd/M1001.cpp | 109 +++++++++++++++++++ Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 4 +- Marlin/src/lcd/ultralcd.cpp | 22 ++-- Marlin/src/module/probe.cpp | 10 +- Marlin/src/sd/cardreader.cpp | 3 +- Marlin/src/sd/cardreader.h | 1 - 15 files changed, 179 insertions(+), 118 deletions(-) create mode 100644 Marlin/src/gcode/sd/M1001.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 370fbaf6ec..00f89662c7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1049,6 +1049,10 @@ #define EVENT_GCODE_SD_STOP "G28XY" // G-code to run on Stop Print (e.g., "G28XY" or "G27") + #if ENABLED(PRINTER_EVENT_LEDS) + #define PE_LEDS_COMPLETED_TIME (30*60) // (seconds) Time to keep the LED "done" color before restoring normal illumination + #endif + /** * Continue after Power-Loss (Creality3D) * diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 7adc8272ea..8130affe30 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -210,6 +210,24 @@ bool wait_for_heatup = true; // For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop #if HAS_RESUME_CONTINUE bool wait_for_user; // = false; + + void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { + #if DISABLED(ADVANCED_PAUSE_FEATURE) + UNUSED(no_sleep); + #endif + KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = true; + if (ms) ms += millis(); // expire time + while (wait_for_user && !(ms && ELAPSED(millis(), ms))) { + idle( + #if ENABLED(ADVANCED_PAUSE_FEATURE) + no_sleep + #endif + ); + } + wait_for_user = false; + } + #endif // Inactivity shutdown @@ -418,53 +436,8 @@ void startOrResumeJob() { } inline void finishSDPrinting() { - - bool did_state = true; - switch (card.sdprinting_done_state) { - - case 1: - if (print_job_timer.duration() > 60) - did_state = queue.enqueue_one_P(PSTR("M31")); - break; - - case 2: - did_state = queue.enqueue_one_P(PSTR("M77")); - break; - - case 3: - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - ui.set_progress_done(); - #endif - break; - - case 4: // Display "Click to Continue..." - #if HAS_LEDS_OFF_FLAG // 30 min timeout with LCD, 1 min without - did_state = queue.enqueue_one_P( - print_job_timer.duration() < 60 ? PSTR("M0Q1P1") : PSTR("M0Q1S" TERN(HAS_LCD_MENU, "1800", "60")) - ); - #endif - break; - - case 5: - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.purge(); - #endif - - #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) - planner.finish_and_disable(); - #endif - - #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) - ui.reselect_last_file(); - #endif - - SERIAL_ECHOLNPGM(STR_FILE_PRINTED); - - default: - did_state = false; - card.sdprinting_done_state = 0; - } - if (did_state) ++card.sdprinting_done_state; + if (queue.enqueue_one_P(PSTR("M1001"))) + marlin_state = MF_RUNNING; } #endif // SDSUPPORT @@ -1209,7 +1182,7 @@ void loop() { #if ENABLED(SDSUPPORT) card.checkautostart(); if (card.flag.abort_sd_printing) abortSDPrinting(); - if (card.sdprinting_done_state) finishSDPrinting(); + if (marlin_state == MF_SD_COMPLETE) finishSDPrinting(); #endif queue.advance(); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 3bce72ab80..e6678c5b18 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -83,6 +83,7 @@ enum MarlinState : uint8_t { MF_PAUSED = _BV(1), MF_WAITING = _BV(2), MF_STOPPED = _BV(3), + MF_SD_COMPLETE = _BV(4), MF_KILLED = _BV(7) }; @@ -98,6 +99,7 @@ extern bool wait_for_heatup; #if HAS_RESUME_CONTINUE extern bool wait_for_user; + void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); #endif // Inactivity shutdown timer diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 2df34176da..4506883f46 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -707,14 +707,13 @@ void MMU2::filament_runout() { if (recover) { LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); BUZZ(200, 404); - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover")); #endif - while (wait_for_user) idle(); + wait_for_user_response(); BUZZ(200, 404); BUZZ(200, 404); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index fb69803ee7..de73163cbd 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -184,7 +184,6 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) const char tool = '0' #if NUM_RUNOUT_SENSORS > 1 @@ -246,13 +245,13 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE); #endif - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging...")); #endif + wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) do_pause_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); wait_for_user = false; @@ -508,13 +507,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked")); #endif + wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { #if HAS_BUZZER filament_change_beep(max_beep_count); @@ -540,8 +539,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout")); #endif - // Wait for LCD click or M108 - while (wait_for_user) idle_no_sleep(); + wait_for_user_response(0, true); // Wait for LCD click or M108 #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_INFO, PSTR("Reheating")); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 1ce1e3d5cb..1f9d710bb4 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -857,7 +857,11 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #if ENABLED(POWER_LOSS_RECOVERY) case 413: M413(); break; // M413: Enable/disable/query Power-Loss Recovery - case 1000: M1000(); break; // M1000: Resume from power-loss + case 1000: M1000(); break; // M1000: [INTERNAL] Resume from power-loss + #endif + + #if ENABLED(SDSUPPORT) + case 1001: M1001(); break; // M1001: [INTERNAL] Handle SD completion #endif #if ENABLED(MAX7219_GCODE) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index c1024ac440..8e5d054d99 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -968,6 +968,10 @@ private: static void M1000(); #endif + #if ENABLED(SDSUPPORT) + static void M1001(); + #endif + #if ENABLED(MAX7219_GCODE) static void M7219(); #endif diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 43b39226f7..190023b090 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -24,23 +24,19 @@ #if HAS_RESUME_CONTINUE -#include "../gcode.h" -#include "../../module/planner.h" - #include "../../inc/MarlinConfig.h" +#include "../gcode.h" + +#include "../../module/planner.h" // for synchronize() +#include "../../MarlinCore.h" // for wait_for_user_response() + #if HAS_LCD_MENU #include "../../lcd/ultralcd.h" -#endif - -#if ENABLED(EXTENSIBLE_UI) +#elif ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #endif -#if HAS_LEDS_OFF_FLAG - #include "../../feature/leds/printer_event_leds.h" -#endif - #if ENABLED(HOST_PROMPT_SUPPORT) #include "../../feature/host_actions.h" #endif @@ -56,18 +52,11 @@ void GcodeSuite::M0_M1() { planner.synchronize(); - #if HAS_LEDS_OFF_FLAG - const bool seenQ = parser.seen('Q'); - if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed - #else - constexpr bool seenQ = false; - #endif - #if HAS_LCD_MENU if (parser.string_arg) ui.set_status(parser.string_arg, true); - else if (!seenQ) { + else { LCD_MESSAGEPGM(MSG_USERWAIT); #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 ui.reset_progress_bar_timeout(); @@ -75,12 +64,10 @@ void GcodeSuite::M0_M1() { } #elif ENABLED(EXTENSIBLE_UI) - if (!seenQ) { - if (parser.string_arg) - ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? - else - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); - } + if (parser.string_arg) + ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? + else + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); #else if (parser.string_arg) { @@ -90,25 +77,15 @@ void GcodeSuite::M0_M1() { #endif - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; - #if ENABLED(HOST_PROMPT_SUPPORT) - if (!seenQ) host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); + host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); #endif - if (ms > 0) ms += millis(); // wait until this time for a click - while (wait_for_user && (ms == 0 || PENDING(millis(), ms))) idle(); - - #if HAS_LEDS_OFF_FLAG - printerEventLEDs.onResumeAfterWait(); - #endif + wait_for_user_response(ms); #if HAS_LCD_MENU - if (!seenQ) ui.reset_status(); + ui.reset_status(); #endif - - wait_for_user = false; } #endif // HAS_RESUME_CONTINUE diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp new file mode 100644 index 0000000000..4261b57f97 --- /dev/null +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -0,0 +1,109 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SDSUPPORT) + +#include "../gcode.h" +#include "../../module/printcounter.h" + +#if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) + #include "../../lcd/ultralcd.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../feature/powerloss.h" +#endif + +#if HAS_LEDS_OFF_FLAG + #include "../../feature/leds/printer_event_leds.h" +#endif + +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../feature/host_actions.h" +#endif + +#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) + #include "../../module/planner.h" +#endif + +#ifndef PE_LEDS_COMPLETED_TIME + #define PE_LEDS_COMPLETED_TIME (30*60) +#endif + +/** + * M1001: Execute actions for SD print completion + */ +void GcodeSuite::M1001() { + + // Report total print time + const bool long_print = print_job_timer.duration() > 60; + if (long_print) gcode.process_subcommands_now_P(PSTR("M31")); + + // Stop the print job timer + gcode.process_subcommands_now_P(PSTR("M77")); + + // Set the progress bar "done" state + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + ui.set_progress_done(); + #endif + + // Purge the recovery file + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.purge(); + #endif + + // Announce SD file completion + SERIAL_ECHOLNPGM(STR_FILE_PRINTED); + + // Update the status LED color + #if HAS_LEDS_OFF_FLAG + if (long_print) { + printerEventLEDs.onPrintCompleted(); + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE)); + #endif + #if ENABLED(HOST_PROMPT_SUPPORT) + host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR); + #endif + wait_for_user_response(1000UL * TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)); + printerEventLEDs.onResumeAfterWait(); + } + #endif + + // Wait for the queue to empty (and "clean"), inject SD_FINISHED_RELEASECOMMAND + #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) + planner.finish_and_disable(); + #endif + + // Re-select the last printed file in the UI + #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) + ui.reselect_last_file(); + #endif +} + +#endif // SDSUPPORT diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 75c13de9c7..8fa22e2c71 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -352,6 +352,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Print Paused"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Printing..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Print Aborted"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Print Done"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("No Move."); PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPED. "); diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index a27e2c9726..ac80870ac8 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -61,16 +61,14 @@ void _man_probe_pt(const xy_pos_t &xy) { float lcd_probe_pt(const xy_pos_t &xy) { _man_probe_pt(xy); - KEEPALIVE_STATE(PAUSED_FOR_USER); ui.defer_status_screen(); - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Delta Calibration in progress"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress")); #endif - while (wait_for_user) idle(); + wait_for_user_response(); ui.goto_previous_screen_no_defer(); return current_position.z; } diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 7ff1440559..bbcb678dd8 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -776,6 +776,13 @@ void MarlinUI::update() { // If the action button is pressed... static bool wait_for_unclick; // = false + auto do_click = [&]{ + wait_for_unclick = true; // - Set debounce flag to ignore continous clicks + lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click + wait_for_user = false; // - Any click clears wait for user + quick_feedback(); // - Always make a click sound + }; + #if ENABLED(TOUCH_BUTTONS) if (touch_buttons) { RESET_STATUS_TIMEOUT(); @@ -796,12 +803,8 @@ void MarlinUI::update() { } } } - else if (!wait_for_unclick && (buttons & EN_C)) { // OK button, if not waiting for a debounce release: - wait_for_unclick = true; // - Set debounce flag to ignore continous clicks - lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - } + else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: + do_click(); } else // keep wait_for_unclick value @@ -810,12 +813,7 @@ void MarlinUI::update() { { // Integrated LCD click handling via button_pressed if (!external_control && button_pressed()) { - if (!wait_for_unclick) { // If not waiting for a debounce release: - wait_for_unclick = true; // - Set debounce flag to ignore continous clicks - lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - } + if (!wait_for_unclick) do_click(); // Handle the click } else wait_for_unclick = false; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 962c230775..6e3f2baa66 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -134,12 +134,10 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() LCD_MESSAGEPGM(MSG_MANUAL_DEPLOY_TOUCHMI); ui.return_to_status(); - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI probe."), CONTINUE_STR); + host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR); #endif - while (wait_for_user) idle(); + wait_for_user_response(); ui.reset_status(); ui.goto_screen(prev_screen); @@ -297,15 +295,13 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { serialprintPGM(ds_str); SERIAL_EOL(); - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe")); #endif - while (wait_for_user) idle(); + wait_for_user_response(); ui.reset_status(); } while( diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index aadd355afd..80e94b88b5 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -49,7 +49,6 @@ // public: card_flags_t CardReader::flag; -uint8_t CardReader::sdprinting_done_state; char CardReader::filename[FILENAME_LENGTH], CardReader::longFilename[LONG_FILENAME_LENGTH]; int8_t CardReader::autostart_index; @@ -1089,7 +1088,7 @@ void CardReader::fileHasFinished() { presort(); #endif - sdprinting_done_state = 1; + marlin_state = MF_SD_COMPLETE; } } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 749ece01d3..955a8b69b3 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -49,7 +49,6 @@ typedef struct { class CardReader { public: - static uint8_t sdprinting_done_state; static card_flags_t flag; // Flags (above) static char filename[FILENAME_LENGTH], // DOS 8.3 filename of the selected item longFilename[LONG_FILENAME_LENGTH]; // Long name of the selected item From 2f7e5cf7ddd04ae0474f104dd1b712b480fe692c Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sat, 28 Mar 2020 09:53:04 -0500 Subject: [PATCH 0066/1454] Fix typo... --- Marlin/src/libs/numtostr.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index ac82bf16f1..1ed315ae07 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -312,7 +312,7 @@ const char* ftostr52sign(const float &f) { // Convert signed float to string with +12.345 format const char* ftostr53sign(const float &f) { - long i = (f * 1000 + (f < 0 ? -5: 5)) / 10; + long i = (f * 10000 + (f < 0 ? -5: 5)) / 10; conv[0] = MINUSOR(i, '+'); conv[1] = DIGIMOD(i, 10000); conv[2] = DIGIMOD(i, 1000); From fc74c6a7b6646cf608f96bdf362a136eb306415e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 29 Mar 2020 00:03:23 +0000 Subject: [PATCH 0067/1454] [cron] Bump distribution date (2020-03-29) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9978e3e6d3..0a2599294a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-28" + #define STRING_DISTRIBUTION_DATE "2020-03-29" #endif /** From b35dc5f0b41dc592dbce29682cf617afc652f11f Mon Sep 17 00:00:00 2001 From: oscarsan1 Date: Sun, 29 Mar 2020 19:37:12 +0200 Subject: [PATCH 0068/1454] Fix Trigorilla 1.4 missing spaces --- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index dcf5ff5a0a..9016028055 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -66,13 +66,13 @@ #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN #else // EEB - #define RAMPS_D8_PINTRIGORILLA_HEATER_BED_PIN + #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN #define FAN_PIN TRIGORILLA_FAN0_PIN // Override pin 4 in pins_RAMPS.h #endif #elif TEMP_SENSOR_BED // EFB (Anycubic Kossel default) #define RAMPS_D9_PIN TRIGORILLA_FAN0_PIN - #define RAMPS_D8_PINTRIGORILLA_HEATER_BED_PIN + #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN #else // EFF #define RAMPS_D9_PIN TRIGORILLA_FAN1_PIN @@ -83,7 +83,7 @@ #define FAN1_PIN TRIGORILLA_FAN1_PIN #endif #define FAN2_PIN TRIGORILLA_FAN2_PIN -#define ORIG_E0_AUTO_FAN_PINTRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config +#define ORIG_E0_AUTO_FAN_PIN TRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config #include "pins_RAMPS.h" From add34aa286bbcbd081aff4a25055505759f3e9f1 Mon Sep 17 00:00:00 2001 From: thisiskeithb Date: Sat, 28 Mar 2020 06:49:59 -0700 Subject: [PATCH 0069/1454] Fix STM32F1 USB Composite Dependency Co-authored-by: Lord-Quake --- platformio.ini | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/platformio.ini b/platformio.ini index 13808d299a..4e801713a0 100644 --- a/platformio.ini +++ b/platformio.ini @@ -301,7 +301,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -316,7 +316,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -332,7 +332,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -348,7 +348,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 From fc11e7217460056473f91dfb7dd574884319f567 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Mar 2020 16:10:55 -0500 Subject: [PATCH 0070/1454] Fix extra unskew call Fixes #17264 --- Marlin/src/module/planner.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index c71a0f61cc..e1a050a459 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1519,10 +1519,6 @@ void Planner::check_axes_activity() { #endif } - - #if ENABLED(SKEW_CORRECTION) - unskew(raw); - #endif } #endif // HAS_LEVELING From 765a9f3471b8a6b67c23f79cc6965e2f795f284a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Mar 2020 16:26:55 -0500 Subject: [PATCH 0071/1454] do_pause_e_move => unscaled_e_move --- Marlin/src/feature/pause.cpp | 31 +++++++++--------------- Marlin/src/feature/pause.h | 2 -- Marlin/src/gcode/feature/camera/M240.cpp | 10 ++------ Marlin/src/lcd/language/language_fr.h | 4 +-- Marlin/src/module/motion.cpp | 13 ++++++++++ Marlin/src/module/motion.h | 2 ++ Marlin/src/module/tool_change.cpp | 6 ++--- 7 files changed, 33 insertions(+), 35 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index de73163cbd..9c615b6ff8 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -134,15 +134,6 @@ static bool ensure_safe_temperature(const PauseMode mode=PAUSE_MODE_SAME) { return thermalManager.wait_for_hotend(active_extruder); } -void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s) { - #if HAS_FILAMENT_SENSOR - runout.reset(); - #endif - current_position.e += length / planner.e_factor[active_extruder]; - line_to_current_position(fr_mm_s); - planner.synchronize(); -} - /** * Load filament into the hotend * @@ -217,7 +208,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif // Slow Load filament - if (slow_load_length) do_pause_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); + if (slow_load_length) unscaled_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); // Fast Load Filament if (fast_load_length) { @@ -226,7 +217,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l planner.settings.retract_acceleration = FILAMENT_CHANGE_FAST_LOAD_ACCEL; #endif - do_pause_e_move(fast_load_length, FILAMENT_CHANGE_FAST_LOAD_FEEDRATE); + unscaled_e_move(fast_load_length, FILAMENT_CHANGE_FAST_LOAD_FEEDRATE); #if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0 planner.settings.retract_acceleration = saved_acceleration; @@ -253,7 +244,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) - do_pause_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); + unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); wait_for_user = false; #else @@ -266,7 +257,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif // Extrude filament to get into hotend - do_pause_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); + unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); } #if ENABLED(HOST_PROMPT_SUPPORT) @@ -331,13 +322,13 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, #endif // Retract filament - do_pause_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); + unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); // Wait for filament to cool safe_delay(FILAMENT_UNLOAD_PURGE_DELAY); // Quickly purge - do_pause_e_move((FILAMENT_UNLOAD_PURGE_RETRACT + FILAMENT_UNLOAD_PURGE_LENGTH) * mix_multiplier, + unscaled_e_move((FILAMENT_UNLOAD_PURGE_RETRACT + FILAMENT_UNLOAD_PURGE_LENGTH) * mix_multiplier, (FILAMENT_UNLOAD_PURGE_FEEDRATE) * mix_multiplier); // Unload filament @@ -346,7 +337,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, planner.settings.retract_acceleration = FILAMENT_CHANGE_UNLOAD_ACCEL; #endif - do_pause_e_move(unload_length * mix_multiplier, (FILAMENT_CHANGE_UNLOAD_FEEDRATE) * mix_multiplier); + unscaled_e_move(unload_length * mix_multiplier, (FILAMENT_CHANGE_UNLOAD_FEEDRATE) * mix_multiplier); #if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0 planner.settings.retract_acceleration = saved_acceleration; @@ -436,7 +427,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float // Initial retract before move to filament change position if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) - do_pause_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); + unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) if (!axes_need_homing()) @@ -631,11 +622,11 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le #if ENABLED(FWRETRACT) // If retracted before goto pause if (fwretract.retracted[active_extruder]) - do_pause_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); + unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); #endif // If resume_position is negative - if (resume_position.e < 0) do_pause_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); + if (resume_position.e < 0) unscaled_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); @@ -644,7 +635,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); #if ADVANCED_PAUSE_RESUME_PRIME != 0 - do_pause_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); + unscaled_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); #endif // Now all extrusion positions are resumed and ready to be confirmed diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 5ac67a565c..f1c8eed4d3 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -83,8 +83,6 @@ extern uint8_t did_pause_print; #define DXC_PASS #endif -void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s); - bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index 3c045a7e68..33ef9bf1a1 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -48,14 +48,8 @@ #ifdef PHOTO_RETRACT_MM inline void e_move_m240(const float length, const feedRate_t &fr_mm_s) { - if (length && thermalManager.hotEnoughToExtrude(active_extruder)) { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - do_pause_e_move(length, fr_mm_s); - #else - current_position.e += length / planner.e_factor[active_extruder]; - line_to_current_position(fr_mm_s); - #endif - } + if (length && thermalManager.hotEnoughToExtrude(active_extruder)) + unscaled_e_move(length, fr_mm_s); } #endif diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index ffa12f39fe..e691d26ab4 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -93,7 +93,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Allumer alim."); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Eteindre alim."); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrusion"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Rétraction"); + PROGMEM Language_Str MSG_RETRACT = _UxGT("Rétractation"); PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveau du lit"); @@ -317,7 +317,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Moteurs bloqués"); PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED"); PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPÉ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Rétraction mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Rétractation mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Ech. rétr. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Vit. rétract°"); PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Saut Z mm"); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index e47727b3ec..834da3ad35 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -55,6 +55,10 @@ #include "../lcd/ultralcd.h" #endif +#if HAS_FILAMENT_SENSOR + #include "../feature/runout.h" +#endif + #if ENABLED(SENSORLESS_HOMING) #include "../feature/tmc_util.h" #endif @@ -332,6 +336,15 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { planner.buffer_line(current_position, fr_mm_s, active_extruder); } +void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s) { + #if HAS_FILAMENT_SENSOR + runout.reset(); + #endif + current_position.e += length / planner.e_factor[active_extruder]; + line_to_current_position(fr_mm_s); + planner.synchronize(); +} + #if IS_KINEMATIC /** diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index f6a75a91a7..4d1ab3bab8 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -184,6 +184,8 @@ void sync_plan_position_e(); */ void line_to_current_position(const feedRate_t &fr_mm_s=feedrate_mm_s); +void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s); + void prepare_line_to_destination(); void _internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 0d91669973..2471581c8c 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -856,7 +856,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { } else { #if ENABLED(ADVANCED_PAUSE_FEATURE) - do_pause_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); + unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); #else current_position.e -= toolchange_settings.swap_length / planner.e_factor[old_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.retract_speed), old_tool); @@ -991,8 +991,8 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) if (should_swap && !too_cold) { #if ENABLED(ADVANCED_PAUSE_FEATURE) - do_pause_e_move(toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.prime_speed)); - do_pause_e_move(toolchange_settings.extra_prime, ADVANCED_PAUSE_PURGE_FEEDRATE); + unscaled_e_move(toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.prime_speed)); + unscaled_e_move(toolchange_settings.extra_prime, ADVANCED_PAUSE_PURGE_FEEDRATE); #else current_position.e += toolchange_settings.swap_length / planner.e_factor[new_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed), new_tool); From d029a098107334aec718c62adf82817b34950f3f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Mar 2020 17:14:06 -0500 Subject: [PATCH 0072/1454] Minor HAL cleanup --- Marlin/src/HAL/LPC1768/main.cpp | 2 +- Marlin/src/HAL/STM32/SoftwareSerial.h | 9 ++------- 2 files changed, 3 insertions(+), 8 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index fb7394344e..d7b05dce9d 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -90,7 +90,7 @@ void HAL_init() { //debug_frmwrk_init(); //_DBG("\n\nDebug running\n"); - // Initialise the SD card chip select pins as soon as possible + // Initialize the SD card chip select pins as soon as possible #if PIN_EXISTS(SS) OUT_WRITE(SS_PIN, HIGH); #endif diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.h b/Marlin/src/HAL/STM32/SoftwareSerial.h index 3799701cfe..504bd6979b 100644 --- a/Marlin/src/HAL/STM32/SoftwareSerial.h +++ b/Marlin/src/HAL/STM32/SoftwareSerial.h @@ -29,9 +29,7 @@ * The latest version of this library can always be found at * http://arduiniana.org. */ - -#ifndef SOFTWARESERIAL_H -#define SOFTWARESERIAL_H +#pragma once #include @@ -64,7 +62,6 @@ class SoftwareSerial : public Stream { uint32_t delta_start = 0; // static data - static bool initialised; static HardwareTimer timer; static const IRQn_Type timer_interrupt_number; static uint32_t timer_interrupt_priority; @@ -91,7 +88,7 @@ class SoftwareSerial : public Stream { public: // public methods - SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic = false); + SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic=false); virtual ~SoftwareSerial(); void begin(long speed); bool listen(); @@ -115,5 +112,3 @@ class SoftwareSerial : public Stream { using Print::write; }; - -#endif // SOFTWARESERIAL_H From 223aa5cc4efdab1ad987e490abe2e3020a7b211e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Mar 2020 17:20:01 -0500 Subject: [PATCH 0073/1454] No unscaled_e_move for CNC --- Marlin/src/module/motion.cpp | 18 ++++++++++-------- Marlin/src/module/motion.h | 4 +++- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 834da3ad35..1cc0a04712 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -336,14 +336,16 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { planner.buffer_line(current_position, fr_mm_s, active_extruder); } -void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s) { - #if HAS_FILAMENT_SENSOR - runout.reset(); - #endif - current_position.e += length / planner.e_factor[active_extruder]; - line_to_current_position(fr_mm_s); - planner.synchronize(); -} +#if EXTRUDERS + void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s) { + #if HAS_FILAMENT_SENSOR + runout.reset(); + #endif + current_position.e += length / planner.e_factor[active_extruder]; + line_to_current_position(fr_mm_s); + planner.synchronize(); + } +#endif #if IS_KINEMATIC diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 4d1ab3bab8..e504f187f9 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -184,7 +184,9 @@ void sync_plan_position_e(); */ void line_to_current_position(const feedRate_t &fr_mm_s=feedrate_mm_s); -void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s); +#if EXTRUDERS + void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s); +#endif void prepare_line_to_destination(); From 9b886c2ad460d93324f9e1a016fefdbbb2e35445 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Mar 2020 18:12:06 -0500 Subject: [PATCH 0074/1454] Load balance some tests --- Marlin/src/pins/rambo/pins_RAMBO.h | 11 +++++++++ Marlin/src/pins/ramps/pins_RAMPS.h | 8 +++--- buildroot/share/tests/mega2560-tests | 37 ---------------------------- buildroot/share/tests/rambo-tests | 35 ++++++++++++++++++++++++++ 4 files changed, 50 insertions(+), 41 deletions(-) diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 0a443cc19a..dec72b8ea7 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -72,6 +72,10 @@ #define Z_MIN_PROBE_PIN 30 #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN 5 +#endif + // // Steppers // @@ -153,6 +157,13 @@ #define SPINDLE_LASER_ENA_PIN 31 // Pullup! #define SPINDLE_DIR_PIN 32 +// +// SPI for Max6675 or Max31855 Thermocouple +// +#ifndef MAX6675_SS_PIN + #define MAX6675_SS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN +#endif + // // M7/M8/M9 - Coolant Control // diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 050932773e..ffe7f7bb1e 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -169,11 +169,11 @@ #define TEMP_BED_PIN 14 // Analog Input #endif +// // SPI for Max6675 or Max31855 Thermocouple -#if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card -#else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) +// +#ifndef MAX6675_SS_PIN + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) #endif // diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index 0bedfd5a73..884ea8be4a 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -12,43 +12,6 @@ set -e #restore_configs #exec_test $1 $2 "Default Configuration" -# -# Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4 -# Test a "Fix Mounted" Probe with Safe Homing, some arc options, -# linear bed leveling, M48, leveling debug, and firmware retraction. -# -restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EEB -opt_set EXTRUDERS 2 -opt_set TEMP_SENSOR_0 -2 -opt_set TEMP_SENSOR_1 1 -opt_set TEMP_SENSOR_BED 2 -opt_set TEMP_SENSOR_PROBE 1 -opt_add TEMP_PROBE_PIN 12 -opt_set TEMP_SENSOR_CHAMBER 3 -opt_add HEATER_CHAMBER_PIN 45 -opt_set GRID_MAX_POINTS_X 16 -opt_set FANMUX0_PIN 53 -opt_disable USE_WATCHDOG -opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED \ - PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ - EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ - BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ - PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ - PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS \ - NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \ - ADVANCED_PAUSE_FEATURE FILAMENT_LOAD_UNLOAD_GCODES FILAMENT_UNLOAD_ALL_EXTRUDERS \ - AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DISTINCT_E_FACTORS \ - SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ - BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ - FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE \ - SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ - HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL -exec_test $1 $2 "RAMPS | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear | Advanced Pause | PLR | LEDs ..." - # # Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders # diff --git a/buildroot/share/tests/rambo-tests b/buildroot/share/tests/rambo-tests index 3f741fcba6..8092059627 100644 --- a/buildroot/share/tests/rambo-tests +++ b/buildroot/share/tests/rambo-tests @@ -33,5 +33,40 @@ opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS exec_test $1 $2 "Rambo CNC Configuration" +# +# Lots of options - Formerly the first Mega2560 test +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO +opt_set EXTRUDERS 2 +opt_set TEMP_SENSOR_0 -2 +opt_set TEMP_SENSOR_1 1 +opt_set TEMP_SENSOR_BED 2 +opt_set TEMP_SENSOR_PROBE 1 +opt_add TEMP_PROBE_PIN 12 +opt_set TEMP_SENSOR_CHAMBER 3 +opt_add HEATER_CHAMBER_PIN 45 +opt_set GRID_MAX_POINTS_X 16 +opt_set FANMUX0_PIN 53 +opt_disable USE_WATCHDOG +opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ + FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED \ + PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ + EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ + BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ + NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ + PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ + PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS \ + NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \ + ADVANCED_PAUSE_FEATURE FILAMENT_LOAD_UNLOAD_GCODES FILAMENT_UNLOAD_ALL_EXTRUDERS \ + AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DISTINCT_E_FACTORS \ + SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ + BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ + FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ + PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE \ + SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ + HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL +exec_test $1 $2 "RAMBO | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear | Advanced Pause | PLR | LEDs ..." + # clean up restore_configs From 747a4bb62360cd6bd44557f117e83140c7cb940c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 30 Mar 2020 00:03:19 +0000 Subject: [PATCH 0075/1454] [cron] Bump distribution date (2020-03-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0a2599294a..7f5c59aeef 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-29" + #define STRING_DISTRIBUTION_DATE "2020-03-30" #endif /** From 0ea26d538bfb883bed57c005a6c0c3a365c31acc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 31 Mar 2020 00:03:22 +0000 Subject: [PATCH 0076/1454] [cron] Bump distribution date (2020-03-31) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7f5c59aeef..33b9bbfbea 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-30" + #define STRING_DISTRIBUTION_DATE "2020-03-31" #endif /** From 96ab16a9dd7167840d9c9a871c43c60bdc7c6b15 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 12:36:59 -0500 Subject: [PATCH 0077/1454] Pulldown for all FastIO headers Co-Authored-By: borsegbr --- Marlin/src/HAL/AVR/fastio.h | 4 ++-- Marlin/src/HAL/DUE/fastio.h | 2 +- Marlin/src/HAL/ESP32/fastio.h | 2 +- Marlin/src/HAL/LPC1768/fastio.h | 2 +- Marlin/src/HAL/SAMD51/fastio.h | 4 ++-- Marlin/src/HAL/TEENSY31_32/fastio.h | 3 ++- Marlin/src/HAL/TEENSY35_36/fastio.h | 3 ++- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 21 ++++++++++--------- 8 files changed, 22 insertions(+), 19 deletions(-) diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index 2246a0f9d0..a45e0f2beb 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -98,9 +98,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) - -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index 6f1f8d8bf2..01abd82049 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -166,7 +166,7 @@ // Set pin as output (wrapper) - reads the pin and sets the output to that value #define SET_OUTPUT(IO) _SET_OUTPUT(IO) // Set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Check if pin is an input #define IS_INPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0) diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h index 9c4efaee9d..09930194d6 100644 --- a/Marlin/src/HAL/ESP32/fastio.h +++ b/Marlin/src/HAL/ESP32/fastio.h @@ -56,7 +56,7 @@ #define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0) // Set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Set pin as output and init #define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) diff --git a/Marlin/src/HAL/LPC1768/fastio.h b/Marlin/src/HAL/LPC1768/fastio.h index 48de5b8fa0..8e8e66db72 100644 --- a/Marlin/src/HAL/LPC1768/fastio.h +++ b/Marlin/src/HAL/LPC1768/fastio.h @@ -104,7 +104,7 @@ /// set pin as output wrapper - reads the pin and sets the output to that value #define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) // set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT /// check if pin is an input wrapper #define IS_INPUT(IO) _IS_INPUT(IO) diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index f6a2675de0..d3b3dc1f63 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -100,9 +100,9 @@ PORT->Group[port].DIRCLR.reg = MASK(pin); \ }while(0) // Set pin as PWM (push pull) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Set pin as PWM (open drain) -#define SET_PWM_OD(IO) SET_OUTPUT_OD(IO) +#define SET_PWM_OD SET_OUTPUT_OD // check if pin is an output #define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \ diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h index 8547fe2b7a..e74920d493 100644 --- a/Marlin/src/HAL/TEENSY31_32/fastio.h +++ b/Marlin/src/HAL/TEENSY31_32/fastio.h @@ -76,8 +76,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h index 8547fe2b7a..e74920d493 100644 --- a/Marlin/src/HAL/TEENSY35_36/fastio.h +++ b/Marlin/src/HAL/TEENSY35_36/fastio.h @@ -76,8 +76,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index ef2b23a3a2..3023a1c6bc 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -176,11 +176,12 @@ #undef MAKE_ARDUINO_PINS } // namespace fast_io - #define SET_INPUT(pin) fast_io::pin::set_input() - #define SET_INPUT_PULLUP(pin) fast_io::pin::set_input(); fast_io::pin::set_high() - #define SET_OUTPUT(pin) fast_io::pin::set_output() - #define READ(pin) fast_io::pin::read() - #define WRITE(pin, value) fast_io::pin::write(value) + #define SET_INPUT(pin) fast_io::pin::set_input() + #define SET_INPUT_PULLUP(pin) do{ fast_io::pin::set_input(); fast_io::pin::set_high(); }while(0) + #define SET_INPUT_PULLDOWN SET_INPUT + #define SET_OUTPUT(pin) fast_io::pin::set_output() + #define READ(pin) fast_io::pin::read() + #define WRITE(pin, value) fast_io::pin::write(value) #ifndef pgm_read_word_far #define pgm_read_word_far pgm_read_word @@ -195,11 +196,11 @@ #endif #define SERIAL_ECHO_START() - #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) - #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(str) Serial.println(str) - #define SERIAL_ECHOLNPAIR(str, val) {Serial.print(F(str)); Serial.println(val);} - #define SERIAL_ECHOPAIR(str, val) {Serial.print(F(str)); Serial.print(val);} + #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) + #define SERIAL_ECHOPGM(str) Serial.print(F(str)) + #define SERIAL_ECHO_MSG(str) Serial.println(str) + #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0) + #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) #define safe_delay delay From 528907cb1604ae2f5c8807e7512e2ea1a98289bf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 12:50:30 -0500 Subject: [PATCH 0078/1454] Additional TERN macros --- Marlin/src/core/macros.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index bcee642368..899baf7359 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -194,6 +194,9 @@ #define DISABLED(V...) DO(DIS,&&,V) #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' +#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' +#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' +#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. From e0e87ca19a57dc42e9eb5e22d044b8f3c1116544 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 12:49:36 -0500 Subject: [PATCH 0079/1454] Fix last arc segment Co-Authored-By: ellensp --- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index b11b1136b6..b0fb299ab2 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -236,7 +236,7 @@ void plan_arc( planner.apply_leveling(raw); #endif - planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, seg_length + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif From ac0a7f2281a5c0df22a3df3fe83d4f112739bbe0 Mon Sep 17 00:00:00 2001 From: Eric Ptak Date: Tue, 31 Mar 2020 20:59:08 +0200 Subject: [PATCH 0080/1454] Fix Fysetc stm32flash usage (#17331) --- buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 1aeaa4d700..67a75f5b47 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -30,7 +30,7 @@ if platform.get_package_dir("tool-stm32duino") != None: env.Replace( UPLOADER=UPLOAD_TOOL, - UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr $UPLOAD_PORT -R -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"") + UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr -R -b 115200 -g 0x8000000 -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"" + " $UPLOAD_PORT") ) # Python callback From c759729478b7b41a4f6d276380249dd482e24bb8 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Tue, 31 Mar 2020 21:13:20 +0200 Subject: [PATCH 0081/1454] STM32F1: Restore M43 build support (#17336) --- Marlin/src/gcode/config/M43.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 2c28da62fb..baf5efb137 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -67,7 +67,11 @@ inline void toggle_pins() { else { watchdog_refresh(); report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing ")); - const bool prior_mode = GET_PINMODE(pin); + #ifdef __STM32F1__ + const auto prior_mode = _GET_MODE(i); + #else + const bool prior_mode = GET_PINMODE(pin); + #endif #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO if (pin == TEENSY_E2) { SET_OUTPUT(TEENSY_E2); @@ -96,7 +100,11 @@ inline void toggle_pins() { watchdog_refresh(); } } - pinMode(pin, prior_mode); + #ifdef __STM32F1__ + _SET_MODE(i, prior_mode); + #else + pinMode(pin, prior_mode); + #endif } SERIAL_EOL(); } From d83ad6f321af6511d35e0396776f557195fcba9f Mon Sep 17 00:00:00 2001 From: Marcio T Date: Tue, 31 Mar 2020 13:22:04 -0600 Subject: [PATCH 0082/1454] Improve / fix FTDI EVE Touch UI (#17338) - Fix timeout and debugging string - Fix check for whether `LCD_TIMEOUT_TO_STATUS` is valid - Fix incorrect debugging message - Make capitalization of callbacks consistent. - Allow Touch UI to use hardware SPI on Einsy boards - Move print stats to About Printer page. - More generic about screen with GPL license. - Add missing handler for power loss event - Less code duplication on status screen and main/advanced menu; more legible - Reorganize advanced and main menu to add more features - Hide home Z button when using Z_SAFE_HOMING - Fix compilation errors when certain features enabled - Fix missing labels in UI - Improve color scheme - Add new preheat menus - Fix incorrect rendering of Marlin logo on boot - Add Level X Axis and Auto calibrate buttons --- Marlin/src/gcode/feature/powerloss/M1000.cpp | 2 +- Marlin/src/gcode/temp/M303.cpp | 2 +- .../ftdi_eve_lib/basic/spi.cpp | 11 + .../ftdi_eve_lib/extended/event_loop.cpp | 2 +- .../ftdi_eve_touch_ui/language/language_en.h | 14 +- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 8 +- .../lib/ftdi_eve_touch_ui/pin_mappings.h | 15 +- .../screens/about_screen.cpp | 76 +++--- .../screens/advanced_settings_menu.cpp | 156 ++++++------ .../base_numeric_adjustment_screen.cpp | 12 +- .../ftdi_eve_touch_ui/screens/base_screen.cpp | 8 +- .../screens/bio_advanced_settings.cpp | 2 +- .../screens/bio_confirm_home_e.cpp | 12 +- .../screens/bio_confirm_home_xyz.cpp | 10 +- .../screens/bio_main_menu.cpp | 4 +- .../ftdi_eve_touch_ui/screens/boot_screen.cpp | 14 +- .../screens/change_filament_screen.cpp | 3 +- .../screens/interface_settings_screen.cpp | 10 +- .../screens/interface_sounds_screen.cpp | 2 +- .../ftdi_eve_touch_ui/screens/main_menu.cpp | 165 +++++++------ .../screens/preheat_menu.cpp | 83 +++++++ .../screens/preheat_timer_screen.cpp | 3 - .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 1 + .../lib/ftdi_eve_touch_ui/screens/screens.h | 9 +- .../screens/status_screen.cpp | 226 +++++++++--------- .../lib/ftdi_eve_touch_ui/theme/colors.h | 210 +++++++++------- .../theme/marlin_bootscreen_landscape.h | 4 +- .../theme/marlin_bootscreen_portrait.h | 4 +- Marlin/src/lcd/extui/ui_api.h | 4 +- Marlin/src/lcd/extui_dgus_lcd.cpp | 6 +- Marlin/src/lcd/extui_example.cpp | 4 +- Marlin/src/lcd/extui_malyan_lcd.cpp | 2 +- Marlin/src/lcd/language/language_en.h | 3 + Marlin/src/module/temperature.cpp | 10 +- 34 files changed, 632 insertions(+), 465 deletions(-) create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index ea2c6e3dab..8d8cdc7557 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M1000() { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); #elif ENABLED(EXTENSIBLE_UI) - ExtUI::OnPowerLossResume(); + ExtUI::onPowerLossResume(); #else SERIAL_ECHO_MSG("Resume requires LCD."); #endif diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 657dd867ee..358a1436b1 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -73,7 +73,7 @@ void GcodeSuite::M303() { if (!WITHIN(e, SI, EI)) { SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); + ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); #endif return; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 7f666be45b..6621ea3cbf 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -38,6 +38,11 @@ namespace FTDI { SET_OUTPUT(CLCD_SPI_CS); WRITE(CLCD_SPI_CS, 1); + #ifdef CLCD_SPI_EXTRA_CS + SET_OUTPUT(CLCD_SPI_EXTRA_CS); + WRITE(CLCD_SPI_EXTRA_CS, 1); + #endif + #ifdef SPI_FLASH_SS SET_OUTPUT(SPI_FLASH_SS); WRITE(SPI_FLASH_SS, 1); @@ -111,12 +116,18 @@ namespace FTDI { ::SPI.beginTransaction(spi_settings); #endif WRITE(CLCD_SPI_CS, 0); + #ifdef CLCD_SPI_EXTRA_CS + WRITE(CLCD_SPI_EXTRA_CS, 0); + #endif delayMicroseconds(1); } // CLCD SPI - Chip Deselect void SPI::spi_ftdi_deselect() { WRITE(CLCD_SPI_CS, 1); + #ifdef CLCD_SPI_EXTRA_CS + WRITE(CLCD_SPI_EXTRA_CS, 1); + #endif #ifndef CLCD_USE_SOFT_SPI ::SPI.endTransaction(); #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index f0f693bfd8..b338758ed1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp @@ -191,7 +191,7 @@ namespace FTDI { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Touch end: ", tag); + SERIAL_ECHOLNPAIR("Touch end: ", pressed_tag); #endif const uint8_t saved_pressed_tag = pressed_tag; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h index e59e1d9468..ebd60aed31 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h @@ -70,13 +70,15 @@ namespace Language_en { PROGMEM Language_Str MSG_PRINT_FINISHED = u8"Print finished"; PROGMEM Language_Str MSG_PRINT_ERROR = u8"Print error"; PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel"; - PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = u8"Portions " COPYRIGHT_SIGN " 2019 Aleph Objects, Inc.\n" - "Portions " COPYRIGHT_SIGN " 2019 Cocoa Press"; - PROGMEM Language_Str MSG_FIRMWARE_FOR_TOOLHEAD = u8"Firmware for toolhead:\n%s\n\n"; + PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; + PROGMEM Language_Str MSG_LICENSE = u8"This program is free software: you can redistribute it and/or modify it under the terms of " + "the GNU General Public License as published by the Free Software Foundation, either version 3 " + "of the License, or (at your option) any later version.\n\nTo view a copy of the GNU General " + "Public License, go to the following location: http://www.gnu.org/licenses."; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; PROGMEM Language_Str MSG_DISPLAY_MENU = u8"Display"; - PROGMEM Language_Str MSG_INTERFACE_SETTINGS = u8"Interface Settings"; + PROGMEM Language_Str MSG_INTERFACE = u8"Interface"; PROGMEM Language_Str MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically"; PROGMEM Language_Str MSG_H_OFFSET = u8"H Offset"; PROGMEM Language_Str MSG_V_OFFSET = u8"V Offset"; @@ -129,7 +131,7 @@ namespace Language_en { PROGMEM Language_Str MSG_SOUND_VOLUME = u8"Sound volume"; PROGMEM Language_Str MSG_SCREEN_LOCK = u8"Screen lock"; PROGMEM Language_Str MSG_BOOT_SCREEN = u8"Boot screen"; - PROGMEM Language_Str MSG_INTERFACE_SOUNDS = u8"Interface Sounds"; + PROGMEM Language_Str MSG_SOUNDS = u8"Sounds"; PROGMEM Language_Str MSG_CLICK_SOUNDS = u8"Click sounds"; PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; @@ -144,12 +146,12 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; + PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; #ifdef TOUCH_UI_LULZBOT_BIO PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; PROGMEM Language_Str MSG_RAISE_PLUNGER = u8"Raise Plunger"; PROGMEM Language_Str MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis"; - PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Auto-level X Axis"; PROGMEM Language_Str MSG_BED_TEMPERATURE = u8"Bed Temperature"; PROGMEM Language_Str MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?"; PROGMEM Language_Str MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?"; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index 96845d4065..bed32cc606 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -131,8 +131,14 @@ namespace ExtUI { } #endif + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + } + #endif + #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 548c6c7439..b5b0f22e11 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -129,12 +129,13 @@ * 9 GND GND GND --> GND * 10 5V 5V 5V --> KILL [3] * - * [1] This configuration is not compatible with the - * EinsyRetro 1.1a because there is a level shifter - * on MISO enabled by SD/USB chip select. + * [1] This configuration allows daisy-chaining of the + * display and SD/USB on EXP2, except for [2] * - * [2] This configuration allows daisy-chaining of the - * display and SD/USB on EXP2. + * [2] The Ultimachine Einsy boards have a level shifter + * on MISO enabled by SD_CSEL chip select, hence it + * is not possible to run both the display and the + * SD/USB on EXP2. * * [3] Archim Rambo provides 5V on this pin. On any other * board, divert this wire from the ribbon cable and @@ -148,4 +149,8 @@ #define CLCD_SPI_CS BTN_EN1 #define CLCD_MOD_RESET BTN_EN2 + + #if MB(EINSY_RAMBO, EINSY_RETRO) && DISABLED(SDSUPPORT) + #define CLCD_SPI_EXTRA_CS SDSS + #endif #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp index afd4402fc1..70acc09071 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp @@ -27,7 +27,7 @@ #include "screens.h" #define GRID_COLS 4 -#define GRID_ROWS 9 +#define GRID_ROWS 7 using namespace FTDI; using namespace Theme; @@ -45,7 +45,32 @@ void AboutScreen::onRedraw(draw_mode_t) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(4,1), + #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) + #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,2) + #define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1) + + #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h + #define INSET_POS(pos) _INSET_POS(pos) + + char about_str[ + strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + + strlen_P(TOOLHEAD_NAME) + 1 + ]; + #ifdef TOOLHEAD_NAME + // If MSG_ABOUT_TOUCH_PANEL_2 has %s, substitute in the toolhead name. + // But this is optional, so squelch the compiler warning here. + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-extra-args" + sprintf_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2), TOOLHEAD_NAME); + #pragma GCC diagnostic pop + #else + strcpy_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); + #endif + + draw_text_box(cmd, HEADING_POS, #ifdef CUSTOM_MACHINE_NAME F(CUSTOM_MACHINE_NAME) #else @@ -53,42 +78,29 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif , OPT_CENTER, font_xlarge ); + draw_text_box(cmd, FW_VERS_POS, progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); + draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); + draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); - #ifdef TOOLHEAD_NAME - char about_str[ - strlen_P(GET_TEXT(FIRMWARE_FOR_TOOLHEAD)) + - strlen_P(TOOLHEAD_NAME) + - strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + 1 - ]; - - sprintf_P(about_str, GET_TEXT(MSG_FIRMWARE_FOR_TOOLHEAD), TOOLHEAD_NAME); - strcat_P (about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); - #endif - - cmd.tag(2); - draw_text_box(cmd, BTN_POS(1,3), BTN_SIZE(4,3), - #ifdef TOOLHEAD_NAME - about_str - #else - GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_2) - #endif - , OPT_CENTER, font_medium - ); - - cmd.tag(0); - draw_text_box(cmd, BTN_POS(1,6), BTN_SIZE(4,2), progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); - - cmd.font(font_medium).colors(action_btn).tag(1).button(BTN_POS(2,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY)); + cmd.font(font_medium) + .colors(normal_btn) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); } bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: GOTO_PREVIOUS(); return true; -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - case 2: GOTO_SCREEN(DeveloperMenu); return true; -#endif - default: return false; + case 1: GOTO_PREVIOUS(); break; + #if ENABLED(PRINTCOUNTER) + case 2: GOTO_SCREEN(StatisticsScreen); break; + #endif + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + case 3: GOTO_SCREEN(DeveloperMenu); break; + #endif + default: return false; } + return true; } #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 6029382838..57137c5d4a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -37,127 +37,116 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .cmd(CLEAR(true,true,true)); } + #ifdef TOUCH_UI_PORTRAIT + #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #define GRID_ROWS 9 + #else + #define GRID_ROWS 8 + #endif + #define GRID_COLS 2 + #define RESTORE_DEFAULTS_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define DISPLAY_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ZPROBE_ZOFFSET_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define VELOCITY_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) + #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) + #else + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #endif + #else + #define GRID_ROWS 6 + #define GRID_COLS 3 + #define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(3,1), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(3,2), BTN_SIZE(1,1) + #define BACKLASH_POS BTN_POS(3,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define DISPLAY_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define RESTORE_DEFAULTS_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define VELOCITY_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 10 - #define GRID_COLS 2 .enabled( #if HAS_BED_PROBE 1 #endif ) - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) + .tag(2) .button( ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) .enabled( #if HAS_CASE_LIGHT 1 #endif ) - .tag(16).button( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) + .tag(16).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) + .tag(3) .button( STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) .enabled( #if HAS_TRINAMIC_CONFIG 1 #endif ) - .tag(13).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) + .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) .enabled( - #if HAS_TRINAMIC_CONFIG + #if ENABLED(SENSORLESS_HOMING) 1 #endif ) - .tag(14).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) + .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled( #if HOTENDS > 1 1 #endif ) - .tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) .enabled( #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) 1 #endif ) - .tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(12).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(15).button( BTN_POS(2,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) - .tag(10).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) - .tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif + .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) + .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) + .tag(15).button( DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) + .tag(9) .button( INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE)) + .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) + .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) + .tag(7) .button( JERK_POS, GET_TEXT_F( + #if DISABLED(CLASSIC_JERK) + MSG_JUNCTION_DEVIATION + #else + JERK_POS + #endif + )) .enabled( #if ENABLED(BACKLASH_GCODE) 1 #endif ) - .tag(8).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) + .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) .colors(action_btn) - .tag(1) .button( BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 6 - #define GRID_COLS 3 - .enabled( - #if HAS_BED_PROBE - 1 - #endif - ) - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - .enabled( - #if HAS_CASE_LIGHT - 1 - #endif - ) - .tag(16).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - .enabled(1) - .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) - .tag(13).button( BTN_POS(3,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) - .tag(14).button( BTN_POS(3,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) - .enabled( - #if ENABLED(BACKLASH_GCODE) - 1 - #endif - ) - .tag(8).button( BTN_POS(3,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) - .enabled( - #if HOTENDS > 1 - 1 - #endif - ) - .tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) - .tag(12).button( BTN_POS(3,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif - .tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(15).button( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) - .tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) - .colors(action_btn) - .tag(1) .button( BTN_POS(3,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #endif + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } } @@ -191,6 +180,8 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 12: GOTO_SCREEN(EndstopStatesScreen); break; #if HAS_TRINAMIC_CONFIG case 13: GOTO_SCREEN(StepperCurrentScreen); break; + #endif + #if ENABLED(SENSORLESS_HOMING) case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; #endif case 15: GOTO_SCREEN(DisplayTuningScreen); break; @@ -201,5 +192,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { } return true; } - #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp index 97e399a403..3e3f1d48a2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp @@ -345,10 +345,14 @@ void BaseNumericAdjustmentScreen::widgets_t::home_buttons(uint8_t tag) { } cmd.font(LAYOUT_FONT); - _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); - _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); - _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); - _button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); + _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); + #if DISABLED(Z_SAFE_HOMING) + _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); + _button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + #else + _button(cmd, tag+3, BTN_POS(9,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + #endif _line++; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp index 77cadabcd7..7e88b7883a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp @@ -46,7 +46,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -66,7 +66,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -78,12 +78,12 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS last_interaction = millis(); #endif } -#ifdef LCD_TIMEOUT_TO_STATUS +#if LCD_TIMEOUT_TO_STATUS uint32_t BaseScreen::last_interaction; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index 6c9f74f93f..ed8bcee557 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -85,7 +85,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #endif ) .tag(12) .button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(14) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .colors(action_btn) .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp index a3254bae9a..79a6112e4f 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp @@ -36,11 +36,13 @@ void BioConfirmHomeE::onRedraw(draw_mode_t) { bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - SpinnerDialogBox::enqueueAndWait_P(F( - "G28 E\n" - AXIS_LEVELING_COMMANDS "\n" - PARK_AND_RELEASE_COMMANDS - )); + #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) + SpinnerDialogBox::enqueueAndWait_P(F( + "G28 E\n" + AXIS_LEVELING_COMMANDS "\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif current_screen.forget(); break; case 2: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp index 883a446b3e..3ae2d680ce 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp @@ -36,10 +36,12 @@ void BioConfirmHomeXYZ::onRedraw(draw_mode_t) { bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - SpinnerDialogBox::enqueueAndWait_P(F( - "G28\n" - PARK_AND_RELEASE_COMMANDS - )); + #ifdef PARK_AND_RELEASE_COMMANDS + SpinnerDialogBox::enqueueAndWait_P(F( + "G28\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif current_screen.forget(); break; case 2: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp index 40ed8479ee..1f6aa45c17 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp @@ -51,7 +51,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) .tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) .tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) - .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(8).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .tag(9).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) @@ -72,7 +72,9 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break; case 4: StatusScreen::unlockMotors(); break; + #ifdef AXIS_LEVELING_COMMANDS case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif case 6: GOTO_SCREEN(TemperatureScreen); break; case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp index 996c12cf23..5e022b58e7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp @@ -80,12 +80,14 @@ void BootScreen::onIdle() { SpinnerDialogBox::hide(); } - if (UIData::animations_enabled()) { - // If there is a startup video in the flash SPI, play - // that, otherwise show a static splash screen. - if (!MediaPlayerScreen::playBootMedia()) - showSplashScreen(); - } + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) + if (UIData::animations_enabled()) { + // If there is a startup video in the flash SPI, play + // that, otherwise show a static splash screen. + if (!MediaPlayerScreen::playBootMedia()) + showSplashScreen(); + } + #endif StatusScreen::loadBitmaps(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp index 2d1e0d6627..2b5963fdf6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp @@ -111,6 +111,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { cmd.cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) .tag(0) #ifdef TOUCH_UI_PORTRAIT .font(font_large) @@ -119,7 +120,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { #endif .text(BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_EXTRUDER_SELECTION)) #ifdef TOUCH_UI_PORTRAIT - .text(BTN_POS(1,7), BTN_SIZE(1,1), F("")) + .text(BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) #else .text(BTN_POS(3,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) .font(font_small) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 3de03579e4..4e165aa448 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -69,7 +69,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0) .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE)) #undef EDGE_R #define EDGE_R 30 .font(font_small) @@ -77,7 +77,9 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); + #endif #undef EDGE_R } @@ -95,16 +97,18 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) .colors(ui_toggle) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) .tag(5).toggle2(BTN_POS(3,5), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::animations_enabled()) + #endif #undef EDGE_R #define EDGE_R 0 #ifdef TOUCH_UI_PORTRAIT .colors(normal_btn) - .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); #else - .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp index 57f520e8ab..48fae863a7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp @@ -71,7 +71,7 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { #define GRID_ROWS 9 .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) #undef EDGE_R #define EDGE_R 30 .font(font_small) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp index 016996e265..5d165edef0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -37,81 +37,89 @@ void MainMenu::onRedraw(draw_mode_t what) { .cmd(CLEAR(true,true,true)); } + #ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 8 + #define GRID_COLS 2 + #define ABOUT_PRINTER_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define MOVE_AXIS_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define DISABLE_STEPPERS_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define LEVEL_BED_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define LEVEL_AXIS_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #else + #define GRID_ROWS 6 + #define GRID_COLS 2 + #define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define ABOUT_PRINTER_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define MOVE_AXIS_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define DISABLE_STEPPERS_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define FILAMENTCHANGE_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define LEVEL_BED_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define LEVEL_AXIS_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) + #endif + if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 - #define GRID_COLS 2 - .tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) - .enabled( - #if ENABLED(NOZZLE_CLEAN_FEATURE) - 1 - #endif + .tag(2).button( AUTO_HOME_POS, GET_TEXT_F(MSG_AUTO_HOME)) + .enabled( + #if ANY(NOZZLE_CLEAN_FEATURE, TOUCH_UI_COCOA_PRESS) + 1 + #endif + ) + .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F( + #if ENABLED(TOUCH_UI_COCOA_PRESS) + MSG_PREHEAT_1 + #else + MSG_CLEAN_NOZZLE + #endif + )) + .tag(4).button( MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS)) + .tag(5).button( DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) + .tag(6).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) + .enabled( + #if DISABLED(TOUCH_UI_LULZBOT_BIO) + 1 + #endif + ) + .tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F( + #if ENABLED(TOUCH_UI_COCOA_PRESS) + MSG_CASE_LIGHT + #else + MSG_FILAMENTCHANGE + #endif + )) + .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .enabled( + #ifdef PRINTCOUNTER + 1 + #endif ) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) - .tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_TEMPERATURE)) - .enabled( - #if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - 1 - #endif + .enabled( + #ifdef AXIS_LEVELING_COMMANDS + 1 + #endif ) - .tag(7).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - .tag(8).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif + .tag(9).button( LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) + .enabled( + #ifdef HAS_LEVELING + 1 + #endif ) - .tag(9).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) - .tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 5 - #define GRID_COLS 2 - .tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) - #if ENABLED(TOUCH_UI_COCOA_PRESS) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_PREHEAT_1)) - #else - .enabled( - #if ENABLED(NOZZLE_CLEAN_FEATURE) - 1 - #endif - ) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) - #endif - .tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TEMPERATURE)) - #if ENABLED(TOUCH_UI_COCOA_PRESS) - .tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - #else - .enabled( - #if DISABLED(TOUCH_UI_LULZBOT_BIO) - 1 - #endif - ) - .tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - #endif - .tag(8).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif - ) - .tag(9).button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) - .tag(10).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #endif + .tag(10).button( LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) + .tag(11).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) + .colors(action_btn) + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } } @@ -122,23 +130,32 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; #if ENABLED(TOUCH_UI_COCOA_PRESS) - case 3: GOTO_SCREEN(PreheatTimerScreen); break; + case 3: GOTO_SCREEN(PreheatMenu); break; #elif ENABLED(NOZZLE_CLEAN_FEATURE) case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; #endif case 4: GOTO_SCREEN(MoveAxisScreen); break; case 5: injectCommands_P(PSTR("M84")); break; case 6: GOTO_SCREEN(TemperatureScreen); break; - #if ENABLED(TOUCH_UI_COCOA_PRESS) + #if ENABLED(TOUCH_UI_COCOA_PRESS) && HAS_CASE_LIGHT case 7: GOTO_SCREEN(CaseLightScreen); break; #else case 7: GOTO_SCREEN(ChangeFilamentScreen); break; #endif case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; -#if ENABLED(PRINTCOUNTER) - case 9: GOTO_SCREEN(StatisticsScreen); break; -#endif - case 10: GOTO_SCREEN(AboutScreen); break; + #ifdef AXIS_LEVELING_COMMANDS + case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif + #ifdef HAS_LEVELING + case 10: SpinnerDialogBox::enqueueAndWait_P(F( + #ifdef BED_LEVELING_COMMANDS + BED_LEVELING_COMMANDS + #else + "G29" + #endif + )); break; + #endif + case 11: GOTO_SCREEN(AboutScreen); break; default: return false; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp new file mode 100644 index 0000000000..f0b5dd887b --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp @@ -0,0 +1,83 @@ +/******************** + * preheat_menu.cpp * + ********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" + +#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_COCOA_PRESS) + +#include "screens.h" + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +void PreheatMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + #define GRID_ROWS 3 + #define GRID_COLS 2 + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.cmd(COLOR_RGB(bg_text_enabled)) + .font(Theme::font_medium) + .text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PREHEAT_1)) + .colors(normal_btn) + .tag(2).button( BTN_POS(1,2), BTN_SIZE(1,1), F("Dark Chocolate")) + .tag(3).button( BTN_POS(2,2), BTN_SIZE(1,1), F("Milk Chocolate")) + .tag(4).button( BTN_POS(1,3), BTN_SIZE(1,1), F("White Chocolate")) + .colors(action_btn) + .tag(1) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); + } +} + +bool PreheatMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: + #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 3: + #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 4: + #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + default: return false; + } + return true; +} + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp index 0a24c30082..7d68ae2d67 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp @@ -77,9 +77,6 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { void PreheatTimerScreen::onEntry() { screen_data.PreheatTimerScreen.start_ms = millis(); - #ifdef COCOA_PRESS_PREHEAT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_SCRIPT)); - #endif } void PreheatTimerScreen::onRedraw(draw_mode_t what) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index 69c1cf1420..ce75462040 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -105,6 +105,7 @@ SCREEN_TABLE { DECL_SCREEN(BioConfirmHomeE), #endif #if ENABLED(TOUCH_UI_COCOA_PRESS) + DECL_SCREEN(PreheatMenu), DECL_SCREEN(PreheatTimerScreen), #endif #if ENABLED(TOUCH_UI_DEVELOPER_MENU) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 02c5b14831..346d122a0f 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -76,6 +76,7 @@ enum { PRINTING_SCREEN_CACHE, #endif #if ENABLED(TOUCH_UI_COCOA_PRESS) + PREHEAT_MENU_CACHE, PREHEAT_TIMER_SCREEN_CACHE, #endif CHANGE_FILAMENT_SCREEN_CACHE, @@ -99,7 +100,7 @@ enum { class BaseScreen : public UIScreen { protected: - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS static uint32_t last_interaction; #endif @@ -314,6 +315,12 @@ class StatusScreen : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + }; + class PreheatTimerScreen : public BaseScreen, public CachedScreen { private: static uint16_t secondsRemaining(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp index e71f200a35..98d0bba759 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp @@ -33,9 +33,9 @@ using namespace FTDI; using namespace Theme; #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 + #define GRID_ROWS 8 #else - #define GRID_ROWS 8 + #define GRID_ROWS 8 #endif void StatusScreen::draw_axis_position(draw_mode_t what) { @@ -43,41 +43,41 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { #define GRID_COLS 3 + #ifdef TOUCH_UI_PORTRAIT + #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define Y_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define Z_LBL_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define X_VAL_POS BTN_POS(2,5), BTN_SIZE(2,1) + #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(2,1) + #define Z_VAL_POS BTN_POS(2,7), BTN_SIZE(2,1) + #else + #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define Y_LBL_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define Z_LBL_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define X_VAL_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define Z_VAL_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + + #define _UNION_POS(x1,y1,w1,h1,x2,y2,w2,h2) x1,y1,max(x1+w1,x2+w2)-x1,max(y1+h1,y2+h2)-y1 + #define UNION_POS(p1, p2) _UNION_POS(p1, p2) + if (what & BACKGROUND) { cmd.tag(6) - #ifdef TOUCH_UI_PORTRAIT - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( BTN_POS(1,5), BTN_SIZE(2,1), F(""), OPT_FLAT) - .button( BTN_POS(1,6), BTN_SIZE(2,1), F(""), OPT_FLAT) - .button( BTN_POS(1,7), BTN_SIZE(2,1), F(""), OPT_FLAT) - - .font(Theme::font_small) - .text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) - .text ( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) - .text ( BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) - - .font(Theme::font_medium) - .fgcolor(Theme::x_axis) .button( BTN_POS(2,5), BTN_SIZE(2,1), F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(2,1), F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( BTN_POS(2,7), BTN_SIZE(2,1), F(""), OPT_FLAT); - #else - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( BTN_POS(1,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - .button( BTN_POS(2,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - .button( BTN_POS(3,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - - .font(Theme::font_small) - .text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) - .text ( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) - .text ( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) - .font(Theme::font_medium) - - .fgcolor(Theme::x_axis) .button( BTN_POS(1,6), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( BTN_POS(3,6), BTN_SIZE(1,1), F(""), OPT_FLAT); - #endif + .fgcolor(Theme::axis_label) + .font(Theme::font_large) + .button( UNION_POS(X_LBL_POS, X_VAL_POS), F(""), OPT_FLAT) + .button( UNION_POS(Y_LBL_POS, Y_VAL_POS), F(""), OPT_FLAT) + .button( UNION_POS(Z_LBL_POS, Z_VAL_POS), F(""), OPT_FLAT) + .font(Theme::font_medium) + .fgcolor(Theme::x_axis) .button( X_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::y_axis) .button( Y_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::z_axis) .button( Z_VAL_POS, F(""), OPT_FLAT) + .font(Theme::font_small) + .text ( X_LBL_POS, GET_TEXT_F(MSG_AXIS_X)) + .text ( Y_LBL_POS, GET_TEXT_F(MSG_AXIS_Y)) + .text ( Z_LBL_POS, GET_TEXT_F(MSG_AXIS_Z)) + .colors(normal_btn); } if (what & FOREGROUND) { @@ -101,16 +101,11 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { else strcpy_P(z_str, PSTR("?")); - cmd.tag(6).font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - .text ( BTN_POS(2,5), BTN_SIZE(2,1), x_str) - .text ( BTN_POS(2,6), BTN_SIZE(2,1), y_str) - .text ( BTN_POS(2,7), BTN_SIZE(2,1), z_str); - #else - .text ( BTN_POS(1,6), BTN_SIZE(1,1), x_str) - .text ( BTN_POS(2,6), BTN_SIZE(1,1), y_str) - .text ( BTN_POS(3,6), BTN_SIZE(1,1), z_str); - #endif + cmd.tag(6) + .font(Theme::font_medium) + .text ( X_VAL_POS, x_str) + .text ( Y_VAL_POS, y_str) + .text ( Z_VAL_POS, z_str); } #undef GRID_COLS @@ -125,49 +120,49 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { void StatusScreen::draw_temperature(draw_mode_t what) { using namespace Theme; + #define TEMP_RECT_1 BTN_POS(1,1), BTN_SIZE(4,2) + #define TEMP_RECT_2 BTN_POS(1,1), BTN_SIZE(8,1) + #define NOZ_1_POS BTN_POS(1,1), BTN_SIZE(4,1) + #define NOZ_2_POS BTN_POS(5,1), BTN_SIZE(4,1) + #define BED_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define FAN_POS BTN_POS(5,2), BTN_SIZE(4,1) + + #define _ICON_POS(x,y,w,h) x, y, w/4, h + #define _TEXT_POS(x,y,w,h) x + w/4, y, w - w/4, h + #define ICON_POS(pos) _ICON_POS(pos) + #define TEXT_POS(pos) _TEXT_POS(pos) + CommandProcessor cmd; if (what & BACKGROUND) { cmd.font(Theme::font_small) - #ifdef TOUCH_UI_PORTRAIT .tag(5) - .fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) - .button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) - .fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) - .tag(0) - .fgcolor(progress) .button( BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button( BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT); - #else - .tag(5) - .fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) - .button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) - .fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) - .tag(0) - .fgcolor(progress) .button( BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button( BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT); - #endif + .fgcolor(temp) .button( TEMP_RECT_1, F(""), OPT_FLAT) + .button( TEMP_RECT_2, F(""), OPT_FLAT) + .fgcolor(fan_speed).button( FAN_POS, F(""), OPT_FLAT) + .tag(0); // Draw Extruder Bitmap on Extruder Temperature Button cmd.tag(5) - .cmd(BITMAP_SOURCE(Extruder_Icon_Info)) - .cmd(BITMAP_LAYOUT(Extruder_Icon_Info)) - .cmd(BITMAP_SIZE (Extruder_Icon_Info)) - .icon (BTN_POS(1,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale) - .icon (BTN_POS(5,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale); + .cmd (BITMAP_SOURCE(Extruder_Icon_Info)) + .cmd (BITMAP_LAYOUT(Extruder_Icon_Info)) + .cmd (BITMAP_SIZE (Extruder_Icon_Info)) + .icon(ICON_POS(NOZ_1_POS), Extruder_Icon_Info, icon_scale) + .icon(ICON_POS(NOZ_2_POS), Extruder_Icon_Info, icon_scale); // Draw Bed Heat Bitmap on Bed Heat Button - cmd.cmd(BITMAP_SOURCE(Bed_Heat_Icon_Info)) - .cmd(BITMAP_LAYOUT(Bed_Heat_Icon_Info)) - .cmd(BITMAP_SIZE (Bed_Heat_Icon_Info)) - .icon (BTN_POS(1,2), BTN_SIZE(1,1), Bed_Heat_Icon_Info, icon_scale); + cmd.cmd (BITMAP_SOURCE(Bed_Heat_Icon_Info)) + .cmd (BITMAP_LAYOUT(Bed_Heat_Icon_Info)) + .cmd (BITMAP_SIZE (Bed_Heat_Icon_Info)) + .icon(ICON_POS(BED_POS), Bed_Heat_Icon_Info, icon_scale); // Draw Fan Percent Bitmap on Bed Heat Button - cmd.cmd(BITMAP_SOURCE(Fan_Icon_Info)) - .cmd(BITMAP_LAYOUT(Fan_Icon_Info)) - .cmd(BITMAP_SIZE (Fan_Icon_Info)) - .icon (BTN_POS(5,2), BTN_SIZE(1,1), Fan_Icon_Info, icon_scale); + cmd.cmd (BITMAP_SOURCE(Fan_Icon_Info)) + .cmd (BITMAP_LAYOUT(Fan_Icon_Info)) + .cmd (BITMAP_SIZE (Fan_Icon_Info)) + .icon(ICON_POS(FAN_POS), Fan_Icon_Info, icon_scale); #ifdef TOUCH_UI_USE_UTF8 load_utf8_bitmaps(cmd); // Restore font bitmap handles @@ -212,10 +207,10 @@ void StatusScreen::draw_temperature(draw_mode_t what) { cmd.tag(5) .font(font_medium) - .text(BTN_POS(2,1), BTN_SIZE(3,1), e0_str) - .text(BTN_POS(6,1), BTN_SIZE(3,1), e1_str) - .text(BTN_POS(2,2), BTN_SIZE(3,1), bed_str) - .text(BTN_POS(6,2), BTN_SIZE(3,1), fan_str); + .text(TEXT_POS(NOZ_1_POS), e0_str) + .text(TEXT_POS(NOZ_2_POS), e1_str) + .text(TEXT_POS(BED_POS), bed_str) + .text(TEXT_POS(FAN_POS), fan_str); } } @@ -225,15 +220,18 @@ void StatusScreen::draw_progress(draw_mode_t what) { CommandProcessor cmd; + #if ENABLED(TOUCH_UI_PORTRAIT) + #define TIME_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define PROGRESS_POS BTN_POS(5,3), BTN_SIZE(4,1) + #else + #define TIME_POS BTN_POS(9,1), BTN_SIZE(4,1) + #define PROGRESS_POS BTN_POS(9,2), BTN_SIZE(4,1) + #endif + if (what & BACKGROUND) { cmd.tag(0).font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .fgcolor(progress) .button(BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button(BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT); - #else - .fgcolor(progress) .button(BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button(BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT); - #endif + .fgcolor(progress).button(TIME_POS, F(""), OPT_FLAT) + .button(PROGRESS_POS, F(""), OPT_FLAT); } if (what & FOREGROUND) { @@ -248,13 +246,8 @@ void StatusScreen::draw_progress(draw_mode_t what) { sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() ); cmd.font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .tag(0).text(BTN_POS(1,3), BTN_SIZE(4,1), time_str) - .text(BTN_POS(5,3), BTN_SIZE(4,1), progress_str); - #else - .tag(0).text(BTN_POS(9,1), BTN_SIZE(4,1), time_str) - .text(BTN_POS(9,2), BTN_SIZE(4,1), progress_str); - #endif + .tag(0).text(TIME_POS, time_str) + .text(PROGRESS_POS, progress_str); } } @@ -266,6 +259,14 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) { if (what & FOREGROUND) { using namespace ExtUI; + #if ENABLED(TOUCH_UI_PORTRAIT) + #define MEDIA_BTN_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define MENU_BTN_POS BTN_POS(3,8), BTN_SIZE(2,1) + #else + #define MEDIA_BTN_POS BTN_POS(1,7), BTN_SIZE(2,2) + #define MENU_BTN_POS BTN_POS(3,7), BTN_SIZE(2,2) + #endif + const bool has_media = isMediaInserted() && !isPrintingFromMedia(); CommandProcessor cmd; @@ -273,42 +274,29 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) { .font(Theme::font_medium) .enabled(has_media) .colors(has_media ? action_btn : normal_btn) - .tag(3).button( - #ifdef TOUCH_UI_PORTRAIT - BTN_POS(1,8), BTN_SIZE(2,1), - #else - BTN_POS(1,7), BTN_SIZE(2,2), - #endif - isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA) - ).colors(!has_media ? action_btn : normal_btn) - #ifdef TOUCH_UI_PORTRAIT - .tag(4).button( BTN_POS(3,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_MENU)); - #else - .tag(4).button( BTN_POS(3,7), BTN_SIZE(2,2), GET_TEXT_F(MSG_BUTTON_MENU)); - #endif + .tag(3).button(MEDIA_BTN_POS, isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA)) + .colors(!has_media ? action_btn : normal_btn) + .tag(4).button( MENU_BTN_POS, GET_TEXT_F(MSG_BUTTON_MENU)); } #undef GRID_COLS } void StatusScreen::draw_status_message(draw_mode_t what, const char* message) { #define GRID_COLS 1 + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define STATUS_POS BTN_POS(1,4), BTN_SIZE(1,1) + #else + #define STATUS_POS BTN_POS(1,3), BTN_SIZE(1,2) + #endif + if (what & BACKGROUND) { CommandProcessor cmd; cmd.fgcolor(Theme::status_msg) .tag(0) - #ifdef TOUCH_UI_PORTRAIT - .button( BTN_POS(1,4), BTN_SIZE(1,1), F(""), OPT_FLAT); - #else - .button( BTN_POS(1,3), BTN_SIZE(1,2), F(""), OPT_FLAT); - #endif + .button( STATUS_POS, F(""), OPT_FLAT); - draw_text_box(cmd, - #ifdef TOUCH_UI_PORTRAIT - BTN_POS(1,4), BTN_SIZE(1,1), - #else - BTN_POS(1,3), BTN_SIZE(1,2), - #endif - message, OPT_CENTER, font_large); + draw_text_box(cmd, STATUS_POS, message, OPT_CENTER, font_large); } #undef GRID_COLS } @@ -326,10 +314,10 @@ void StatusScreen::setStatusMessage(const char* message) { .cmd(CLEAR(true,true,true)); draw_temperature(BACKGROUND); - draw_progress(BACKGROUND); - draw_axis_position(BACKGROUND); draw_status_message(BACKGROUND, message); draw_interaction_buttons(BACKGROUND); + draw_progress(BACKGROUND); + draw_axis_position(BACKGROUND); storeBackground(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h index 933e91db80..e2770d8116 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h @@ -24,121 +24,149 @@ #pragma once namespace Theme { - #ifdef TOUCH_UI_LULZBOT_BIO - // The Lulzbot Bio uses the color PANTONE 2175C on the case silkscreen. - // This translates to HSL(208°, 100%, 39%) as an accent color on the GUI. + #if ENABLED(TOUCH_UI_COCOA_THEME) + constexpr int accent_hue = 23; - constexpr int accent_hue = 208; - constexpr float accent_sat = 0.5; - - constexpr uint32_t logo_bg_rgb = 0xffffff; - constexpr uint32_t logo_fill_rgb = 0xffffff; - constexpr uint32_t logo_stroke_rgb = hsl_to_rgb(accent_hue, 1.0, 0.39); + // Browns and Oranges + constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest + constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263); + constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443); + constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537); + constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539); + constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest #else - // The Lulzbot logo uses the color PANTONE 382c. - // This translates to HSL(68°, 68%, 52%) as an accent color on the GUI. + // Use linear accent colors - constexpr int accent_hue = 68; - constexpr float accent_sat = 0.68; + #if ANY(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME) + // Dark blue accent colors + constexpr int accent_hue = 216; + constexpr float accent_sat = 0.7; + #else + // Green accent colors + constexpr int accent_hue = 68; + constexpr float accent_sat = 0.68; + #endif - constexpr uint32_t logo_bg_rgb = hsl_to_rgb(accent_hue, 0.77, 0.64); - constexpr uint32_t logo_fill_rgb = hsl_to_rgb(accent_hue, 0.68, 0.52); // Lulzbot Green - constexpr uint32_t logo_stroke_rgb = 0x000000; - #endif - - // Shades of accent color - - #ifdef TOUCH_UI_COCOA_PRESS - constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest - constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263); - constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443); - constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537); - constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539); - constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest - #else - constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); // Darkest - constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39); - constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52); - constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65); - constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78); - constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest + // Shades of accent color + constexpr uint32_t accent_color_0 = hsl_to_rgb(accent_hue, accent_sat, 0.15); // Darkest + constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); + constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39); + constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52); + constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65); + constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78); + constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest #endif // Shades of gray - constexpr float gray_sat = 0.14; + constexpr float gray_sat = 0.14; + constexpr uint32_t gray_color_0 = hsl_to_rgb(accent_hue, gray_sat, 0.15); // Darkest + constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); + constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); + constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); + constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65); + constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78); + constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest - constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); // Darkest - constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); - constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); - constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65); - constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78); - constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t theme_darkest = accent_color_1; + constexpr uint32_t theme_dark = accent_color_4; - #if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - // Lulzbot TAZ Pro - constexpr uint32_t theme_darkest = gray_color_1; - constexpr uint32_t theme_dark = gray_color_2; + constexpr uint32_t bg_color = gray_color_0; + constexpr uint32_t axis_label = gray_color_1; - constexpr uint32_t bg_color = theme_darkest; - constexpr uint32_t bg_text_disabled = theme_dark; - constexpr uint32_t bg_text_enabled = 0xFFFFFF; - constexpr uint32_t bg_normal = theme_darkest; + constexpr uint32_t bg_text_enabled = accent_color_6; + constexpr uint32_t bg_text_disabled = gray_color_0; + constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t fg_disabled = gray_color_0; + constexpr uint32_t fg_normal = accent_color_0; + constexpr uint32_t fg_action = accent_color_1; - constexpr uint32_t fg_normal = theme_dark; - constexpr uint32_t fg_action = accent_color_2; - constexpr uint32_t fg_disabled = theme_darkest; + constexpr uint32_t logo_bg_rgb = accent_color_1; + constexpr uint32_t logo_fill_rgb = accent_color_0; + constexpr uint32_t logo_stroke_rgb = accent_color_4; + #elif ANY(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME) + constexpr uint32_t theme_darkest = accent_color_1; + constexpr uint32_t theme_dark = accent_color_4; + + constexpr uint32_t bg_color = 0xFFFFFF; + constexpr uint32_t axis_label = gray_color_5; + + constexpr uint32_t bg_text_enabled = accent_color_1; + constexpr uint32_t bg_text_disabled = gray_color_1; + constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t fg_disabled = gray_color_6; + constexpr uint32_t fg_normal = accent_color_1; + constexpr uint32_t fg_action = accent_color_4; + + constexpr uint32_t logo_bg_rgb = accent_color_5; + constexpr uint32_t logo_fill_rgb = accent_color_6; + constexpr uint32_t logo_stroke_rgb = accent_color_2; #else - // Lulzbot Bio - constexpr uint32_t theme_darkest = accent_color_1; - constexpr uint32_t theme_dark = accent_color_4; + constexpr uint32_t theme_darkest = gray_color_1; + constexpr uint32_t theme_dark = gray_color_2; - constexpr uint32_t bg_color = 0xFFFFFF; - constexpr uint32_t bg_text_disabled = gray_color_1; - constexpr uint32_t bg_text_enabled = accent_color_1; - constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t bg_color = gray_color_1; + constexpr uint32_t axis_label = gray_color_2; - constexpr uint32_t fg_normal = accent_color_1; - constexpr uint32_t fg_action = accent_color_4; - constexpr uint32_t fg_disabled = gray_color_6; + constexpr uint32_t bg_text_enabled = 0xFFFFFF; + constexpr uint32_t bg_text_disabled = gray_color_2; + constexpr uint32_t bg_normal = gray_color_1; + constexpr uint32_t fg_disabled = gray_color_1; + constexpr uint32_t fg_normal = gray_color_2; + constexpr uint32_t fg_action = accent_color_2; - constexpr uint32_t shadow_rgb = gray_color_6; - constexpr uint32_t stroke_rgb = accent_color_1; - constexpr uint32_t fill_rgb = accent_color_3; - constexpr uint32_t syringe_rgb = accent_color_5; + constexpr uint32_t logo_bg_rgb = accent_color_4; + constexpr uint32_t logo_fill_rgb = accent_color_3; + constexpr uint32_t logo_stroke_rgb = 0x000000; #endif - constexpr uint32_t x_axis = 0xFF0000; - constexpr uint32_t y_axis = 0x00BB00; - constexpr uint32_t z_axis = 0x0000BF; - constexpr uint32_t e_axis = gray_color_2; - constexpr uint32_t feedrate = gray_color_2; - constexpr uint32_t other = gray_color_2; + constexpr uint32_t shadow_rgb = gray_color_6; + constexpr uint32_t stroke_rgb = accent_color_1; + constexpr uint32_t fill_rgb = accent_color_3; + constexpr uint32_t syringe_rgb = accent_color_5; + + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26); + constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.13); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.10); + #else + constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.5); + constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.37); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.37); + #endif + constexpr uint32_t e_axis = axis_label; + constexpr uint32_t feedrate = axis_label; + constexpr uint32_t other = axis_label; // Status screen - constexpr uint32_t progress = gray_color_2; - constexpr uint32_t status_msg = gray_color_2; - constexpr uint32_t fan_speed = 0x377198; - constexpr uint32_t temp = 0x892c78; - constexpr uint32_t axis_label = gray_color_2; + constexpr uint32_t progress = axis_label; + constexpr uint32_t status_msg = axis_label; + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t fan_speed = hsl_to_rgb(240, 0.5, 0.13); + constexpr uint32_t temp = hsl_to_rgb(343, 1.0, 0.23); + #else + constexpr uint32_t fan_speed = hsl_to_rgb(204, 0.47, 0.41); + constexpr uint32_t temp = hsl_to_rgb(311, 0.51, 0.35); + #endif - constexpr uint32_t disabled_icon = gray_color_1; + constexpr uint32_t disabled_icon = gray_color_1; // Calibration Registers Screen - constexpr uint32_t transformA = 0x3010D0; - constexpr uint32_t transformB = 0x4010D0; - constexpr uint32_t transformC = 0x5010D0; - constexpr uint32_t transformD = 0x6010D0; - constexpr uint32_t transformE = 0x7010D0; - constexpr uint32_t transformF = 0x8010D0; - constexpr uint32_t transformVal = 0x104010; + constexpr uint32_t transformA = 0x3010D0; + constexpr uint32_t transformB = 0x4010D0; + constexpr uint32_t transformC = 0x5010D0; + constexpr uint32_t transformD = 0x6010D0; + constexpr uint32_t transformE = 0x7010D0; + constexpr uint32_t transformF = 0x8010D0; + constexpr uint32_t transformVal = 0x104010; - constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; - constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; - constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; - constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; - constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; - constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; + constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; + constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; + constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; + constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; + constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; + constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; // Temperature color scale diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h index 5e01f0471c..a65cbea52a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h @@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0xADF3, 0x546C, 0x419D, 0x546F, 0x3D05, #define LOGO_BACKGROUND logo_bg_rgb #define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ - LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) + LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \ + LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h index a5af7a14cd..a9c1d4049e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h @@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0x3C19, 0x70C5, 0x371A, 0x7159, 0x3302, #define LOGO_BACKGROUND logo_bg_rgb #define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ - LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) + LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \ + LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 61fecaed46..01e0d1b7a3 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -341,10 +341,10 @@ namespace ExtUI { void onConfigurationStoreWritten(bool success); void onConfigurationStoreRead(bool success); #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume(); + void onPowerLossResume(); #endif #if HAS_PID_HEATING - void OnPidTuning(const result_t rst); + void onPidTuning(const result_t rst); #endif }; diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 66a58f82dc..855d09033e 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -123,7 +123,7 @@ namespace ExtUI { } #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume() { + void onPowerLossResume() { // Called on resume from power-loss ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); } @@ -131,9 +131,9 @@ namespace ExtUI { #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - SERIAL_ECHOLNPAIR("OnPidTuning:",rst); + SERIAL_ECHOLNPAIR("onPidTuning:",rst); switch(rst) { case PID_BAD_EXTRUDER_NUM: ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_BAD_EXTRUDER_NUM)); diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 741787dbe6..5c9a193ded 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -94,13 +94,13 @@ namespace ExtUI { } #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume() { + void onPowerLossResume() { // Called on resume from power-loss } #endif #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result } #endif diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 0bb8060b07..ddb8b846cb 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -483,7 +483,7 @@ namespace ExtUI { void onLoadSettings(const char*) {} void onConfigurationStoreWritten(bool) {} void onConfigurationStoreRead(bool) {} - void OnPidTuning(const result_t) {} + void onPidTuning(const result_t) {} } #endif // MALYAN_LCD diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 8fa22e2c71..a52d9652ac 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -602,6 +602,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 4e49fcfa24..4018c7586c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -411,7 +411,7 @@ volatile bool Temperature::raw_temps_ready = false; if (target > GHV(BED_MAXTEMP - 10, temp_range[heater].maxtemp - 15)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); + ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); #endif return; } @@ -527,7 +527,7 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); + ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); #endif break; } @@ -572,7 +572,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif if (((ms - t1) + (ms - t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); + ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); #endif SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; @@ -623,7 +623,7 @@ volatile bool Temperature::raw_temps_ready = false; printerEventLEDs.onPidTuningDone(color); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_DONE); + ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); #endif goto EXIT_M303; @@ -637,7 +637,7 @@ volatile bool Temperature::raw_temps_ready = false; printerEventLEDs.onPidTuningDone(color); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_DONE); + ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); #endif EXIT_M303: From e7f020f3f208db23450c845a6c4b67d784a64058 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 14:42:32 -0500 Subject: [PATCH 0083/1454] Shorten some internal pin names --- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 36 +++++++++++----------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index 9016028055..f32f006e92 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -47,43 +47,43 @@ #endif // Labeled pins -#define TRIGORILLA_HEATER_BED_PIN 8 -#define TRIGORILLA_HEATER_0_PIN 10 -#define TRIGORILLA_HEATER_1_PIN 45 // Anycubic Kossel: Unused +#define TG_HEATER_BED_PIN 8 +#define TG_HEATER_0_PIN 10 +#define TG_HEATER_1_PIN 45 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan -#define TRIGORILLA_FAN1_PIN 7 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN2_PIN 44 // Anycubic Kossel: Hotend fan +#define TG_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan +#define TG_FAN1_PIN 7 // Anycubic Kossel: Unused +#define TG_FAN2_PIN 44 // Anycubic Kossel: Hotend fan // Remap MOSFET pins to common usages: -#define RAMPS_D10_PIN TRIGORILLA_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h +#define RAMPS_D10_PIN TG_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h #if HOTENDS > 1 // EEF and EEB - #define RAMPS_D9_PIN TRIGORILLA_HEATER_1_PIN + #define RAMPS_D9_PIN TG_HEATER_1_PIN #if !TEMP_SENSOR_BED // EEF - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D8_PIN TG_FAN0_PIN #else // EEB - #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN - #define FAN_PIN TRIGORILLA_FAN0_PIN // Override pin 4 in pins_RAMPS.h + #define RAMPS_D8_PIN TG_HEATER_BED_PIN + #define FAN_PIN TG_FAN0_PIN // Override pin 4 in pins_RAMPS.h #endif #elif TEMP_SENSOR_BED // EFB (Anycubic Kossel default) - #define RAMPS_D9_PIN TRIGORILLA_FAN0_PIN - #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN + #define RAMPS_D9_PIN TG_FAN0_PIN + #define RAMPS_D8_PIN TG_HEATER_BED_PIN #else // EFF - #define RAMPS_D9_PIN TRIGORILLA_FAN1_PIN - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D9_PIN TG_FAN1_PIN + #define RAMPS_D8_PIN TG_FAN0_PIN #endif #if HOTENDS > 1 || TEMP_SENSOR_BED // EEF, EEB, EFB - #define FAN1_PIN TRIGORILLA_FAN1_PIN + #define FAN1_PIN TG_FAN1_PIN #endif -#define FAN2_PIN TRIGORILLA_FAN2_PIN -#define ORIG_E0_AUTO_FAN_PIN TRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config +#define FAN2_PIN TG_FAN2_PIN +#define ORIG_E0_AUTO_FAN_PIN TG_FAN2_PIN // Used in Anycubic Kossel example config #include "pins_RAMPS.h" From 015c4e6fbdd28f5c4cb5fc987d4f4ae513b1c13d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 14:40:06 -0500 Subject: [PATCH 0084/1454] Version 2.0.5.3 --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 91cc6144cd..b4e51841b3 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.0.5.2" +//#define SHORT_BUILD_VERSION "2.0.5.3" /** * Verbose version identifier which should contain a reference to the location diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d42888b242..a5960c16b2 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.0.5.2" + #define SHORT_BUILD_VERSION "2.0.5.3" #endif /** From 5236889377c3cef48644696372db7e5bb2a92d3e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 1 Apr 2020 00:03:36 +0000 Subject: [PATCH 0085/1454] [cron] Bump distribution date (2020-04-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 33b9bbfbea..00d24330a6 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-31" + #define STRING_DISTRIBUTION_DATE "2020-04-01" #endif /** From 178ca2bcdffcdd185cd38ba77627ee6e64cbec0b Mon Sep 17 00:00:00 2001 From: Marcelo Castagna Date: Tue, 31 Mar 2020 21:13:37 -0300 Subject: [PATCH 0086/1454] Fix M710 report formatting (#17356) --- Marlin/src/gcode/feature/controllerfan/M710.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index e00fa77d62..c19919b2d4 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -29,11 +29,11 @@ void M710_report(const bool forReplay) { if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); } - SERIAL_ECHOLNPAIR("M710 " - "S", int(controllerFan.settings.active_speed), - "I", int(controllerFan.settings.idle_speed), - "A", int(controllerFan.settings.auto_mode), - "D", controllerFan.settings.duration, + SERIAL_ECHOLNPAIR(" M710" + " S", int(controllerFan.settings.active_speed), + " I", int(controllerFan.settings.idle_speed), + " A", int(controllerFan.settings.auto_mode), + " D", controllerFan.settings.duration, " ; (", (int(controllerFan.settings.active_speed) * 100) / 255, "%" " ", (int(controllerFan.settings.idle_speed) * 100) / 255, "%)" ); From 0518dec60d0931745efa2812fa388f33d68cfa29 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 1 Apr 2020 12:16:01 -0700 Subject: [PATCH 0087/1454] Correct link to Configurations (#17370) --- config/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/README.md b/config/README.md index 284a856215..f4dfd9aedf 100644 --- a/config/README.md +++ b/config/README.md @@ -1,3 +1,3 @@ # Where have all the configurations gone? -## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.5.2.zip +## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.5.zip From 192c7c27b9130d5e13f6a1a96ccf490c48d2e26c Mon Sep 17 00:00:00 2001 From: Simon Jouet Date: Wed, 1 Apr 2020 22:20:38 +0100 Subject: [PATCH 0088/1454] Fix extra TMC serial begin calls (#17351) --- Marlin/src/module/stepper/trinamic.cpp | 43 ++++++++++++++++---------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 14598f9c73..f0ac48f514 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -331,115 +331,126 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #endif #endif + enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; + void tmc_serial_begin() { + struct { + const void *ptr[TMCAxis::TOTAL]; + bool began(const TMCAxis a, const void * const p) { + LOOP_L_N(i, a) if (p == ptr[i]) return true; + ptr[a] = p; return false; + }; + } sp_helper; + #define HW_SERIAL_BEGIN(A) do{ if (sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ + A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) #if AXIS_HAS_UART(X) #ifdef X_HARDWARE_SERIAL - X_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(X); #else stepperX.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(X2) #ifdef X2_HARDWARE_SERIAL - X2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(X2); #else stepperX2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y) #ifdef Y_HARDWARE_SERIAL - Y_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Y); #else stepperY.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y2) #ifdef Y2_HARDWARE_SERIAL - Y2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Y2); #else stepperY2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z) #ifdef Z_HARDWARE_SERIAL - Z_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z); #else stepperZ.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z2) #ifdef Z2_HARDWARE_SERIAL - Z2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z2); #else stepperZ2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z3) #ifdef Z3_HARDWARE_SERIAL - Z3_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z3); #else stepperZ3.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z4) #ifdef Z4_HARDWARE_SERIAL - Z4_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z4); #else stepperZ4.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL - E0_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E0); #else stepperE0.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E1) #ifdef E1_HARDWARE_SERIAL - E1_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E1); #else stepperE1.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E2) #ifdef E2_HARDWARE_SERIAL - E2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E2); #else stepperE2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E3) #ifdef E3_HARDWARE_SERIAL - E3_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E3); #else stepperE3.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E4) #ifdef E4_HARDWARE_SERIAL - E4_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E4); #else stepperE4.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E5) #ifdef E5_HARDWARE_SERIAL - E5_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E5); #else stepperE5.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E6) #ifdef E6_HARDWARE_SERIAL - E6_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E6); #else stepperE6.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E7) #ifdef E7_HARDWARE_SERIAL - E7_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E7); #else stepperE7.beginSerial(TMC_BAUD_RATE); #endif From c47bdae9f20207b08f3f8b581c2e9a00bbf6b15b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 2 Apr 2020 00:03:23 +0000 Subject: [PATCH 0089/1454] [cron] Bump distribution date (2020-04-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 00d24330a6..0316c69672 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-01" + #define STRING_DISTRIBUTION_DATE "2020-04-02" #endif /** From 7f5dc7b91920ffd4ecd8b70e58bc97cc6be39fa2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 15:00:43 -0500 Subject: [PATCH 0090/1454] More 8 extruders (TMC) support --- Marlin/src/module/configuration_store.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 2ecc9299c9..b2c728fbe0 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -37,7 +37,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V76" +#define EEPROM_VERSION "V77" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -134,10 +134,10 @@ #pragma pack(push, 1) // No padding between variables -typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t; -typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_hybrid_threshold_t; -typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t; -typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t; +typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; +typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; +typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t; +typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; // Limit an index to an array size #define ALIM(I,ARR) _MIN(I, COUNT(ARR) - 1) From 514afddeb4b3a7ede9ff481504aae69219a95f68 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 18:53:58 -0500 Subject: [PATCH 0091/1454] Minor code cleanup --- Marlin/src/feature/tmc_util.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 4 ++-- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 8 +------ Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 1 - Marlin/src/lcd/ultralcd.cpp | 6 ++--- Marlin/src/module/configuration_store.cpp | 6 ++--- Marlin/src/module/temperature.cpp | 22 ++++++------------- 8 files changed, 17 insertions(+), 34 deletions(-) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index e5e69eed50..bfc2e1a555 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -1254,7 +1254,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z #endif } - if (axis_connection) ui.set_status_P(GET_TEXT(MSG_ERROR_TMC)); + if (axis_connection) LCD_MESSAGEPGM(MSG_ERROR_TMC); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 9ea298f02d..20867b4fea 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2164,7 +2164,7 @@ #define SHARED_SD_CARD #endif #if DISABLED(SHARED_SD_CARD) - #define INIT_SDCARD_ON_BOOT + #define INIT_SDCARD_ON_BOOT 1 #endif #endif diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index ee025f6585..3c89d1803c 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -367,11 +367,11 @@ void MarlinUI::init_lcd() { } bool MarlinUI::detected() { - return true + return (true #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE) && lcd.LcdDetected() == 1 #endif - ; + ); } #if HAS_SLOW_BUTTONS diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index fc7656f1cd..4e07999bf6 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -244,13 +244,7 @@ void MarlinUI::init_lcd() { #if DISABLED(MKS_LCD12864B) #if PIN_EXISTS(LCD_BACKLIGHT) - OUT_WRITE(LCD_BACKLIGHT_PIN, ( - #if ENABLED(DELAYED_BACKLIGHT_INIT) - LOW // Illuminate after reset - #else - HIGH // Illuminate right away - #endif - )); + OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away #endif #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index 6ac84c2bb0..bd73e811d1 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -441,7 +441,6 @@ void DGUSScreenVariableHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variab DGUSLCD_SendStringToDisplay(var); } - void DGUSScreenVariableHandler::SDCardInserted() { top_file = 0; auto cs = ScreenHandler.getCurrentScreen(); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index bbcb678dd8..ff0331eb20 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -351,10 +351,8 @@ void MarlinUI::init() { #endif #endif - #if HAS_ENCODER_ACTION - #if HAS_SLOW_BUTTONS - slow_buttons = 0; - #endif + #if HAS_ENCODER_ACTION && HAS_SLOW_BUTTONS + slow_buttons = 0; #endif update_buttons(); diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index b2c728fbe0..a2beb322f9 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -1391,7 +1391,7 @@ void MarlinSettings::postprocess() { DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - ui.set_status_P(GET_TEXT(MSG_ERR_EEPROM_VERSION)); + LCD_MESSAGEPGM(MSG_ERR_EEPROM_VERSION); #endif eeprom_error = true; } @@ -2199,7 +2199,7 @@ void MarlinSettings::postprocess() { DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)), " Size: ", datasize()); #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - ui.set_status_P(GET_TEXT(MSG_ERR_EEPROM_INDEX)); + LCD_MESSAGEPGM(MSG_ERR_EEPROM_INDEX); #endif } else if (working_crc != stored_crc) { @@ -2207,7 +2207,7 @@ void MarlinSettings::postprocess() { DEBUG_ERROR_START(); DEBUG_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - ui.set_status_P(GET_TEXT(MSG_ERR_EEPROM_CRC)); + LCD_MESSAGEPGM(MSG_ERR_EEPROM_CRC); #endif } else if (!validating) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 4018c7586c..42c79fdd19 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -542,22 +542,14 @@ volatile bool Temperature::raw_temps_ready = false; // Make sure heating is actually working #if WATCH_BED || WATCH_HOTENDS - if ( - #if WATCH_BED && WATCH_HOTENDS - true - #elif WATCH_HOTENDS - !isbed - #else - isbed - #endif - ) { - if (!heated) { // If not yet reached target... - if (current_temp > next_watch_temp) { // Over the watch temp? - next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for - temp_change_ms = ms + watch_temp_period * 1000UL; // - move the expiration timer up - if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached + if (BOTH(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS)) { + if (!heated) { // If not yet reached target... + if (current_temp > next_watch_temp) { // Over the watch temp? + next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for + temp_change_ms = ms + watch_temp_period * 1000UL; // - move the expiration timer up + if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } - else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired + else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired _temp_error(heater, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } else if (current_temp < target - (MAX_OVERSHOOT_PID_AUTOTUNE)) // Heated, then temperature fell too far? From 62e8c2dd871f62d80122fe919d065ee3a3e5d520 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 23:50:08 -0500 Subject: [PATCH 0092/1454] Fix up 'system' includes --- Marlin/src/HAL/ESP32/eeprom_impl.cpp | 2 +- Marlin/src/HAL/SAMD51/QSPIFlash.h | 2 +- Marlin/src/feature/digipot/digipot_mcp4018.cpp | 4 ++-- Marlin/src/feature/digipot/digipot_mcp4451.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/HAL/ESP32/eeprom_impl.cpp b/Marlin/src/HAL/ESP32/eeprom_impl.cpp index dbfee14055..f36aabf28e 100644 --- a/Marlin/src/HAL/ESP32/eeprom_impl.cpp +++ b/Marlin/src/HAL/ESP32/eeprom_impl.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) #include "../shared/eeprom_api.h" -#include "EEPROM.h" +#include #define EEPROM_SIZE 4096 diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h index 7f75286ebf..b6f22769ff 100644 --- a/Marlin/src/HAL/SAMD51/QSPIFlash.h +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h @@ -29,7 +29,7 @@ #pragma once -#include "Adafruit_SPIFlashBase.h" +#include // This class extends Adafruit_SPIFlashBase by adding caching support. // diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index e8df4a475f..ebfbee794a 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -24,8 +24,8 @@ #if BOTH(DIGIPOT_I2C, DIGIPOT_MCP4018) -#include "Stream.h" -#include "utility/twi.h" +#include +#include #include //https://github.com/stawel/SlowSoftI2CMaster // Settings for the I2C based DIGIPOT (MCP4018) based on WT150 diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index 1183c96aa5..79bb6eb3c2 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -24,7 +24,7 @@ #if ENABLED(DIGIPOT_I2C) && DISABLED(DIGIPOT_MCP4018) -#include "Stream.h" +#include #include #if MB(MKS_SBASE) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 42c79fdd19..af2f1a10e8 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -37,7 +37,7 @@ #endif #if ENABLED(MAX6675_IS_MAX31865) - #include "Adafruit_MAX31865.h" + #include #ifndef MAX31865_CS_PIN #define MAX31865_CS_PIN MAX6675_SS_PIN // HW:49 SW:65 for example #endif From f263782f1b1fa981c292f6cdeea8e00bc6f73df3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 23:50:32 -0500 Subject: [PATCH 0093/1454] Fix ESP32 eeprom flag --- Marlin/src/HAL/ESP32/eeprom_impl.cpp | 4 ++-- Marlin/src/HAL/ESP32/inc/Conditionals_post.h | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/ESP32/eeprom_impl.cpp b/Marlin/src/HAL/ESP32/eeprom_impl.cpp index f36aabf28e..1c005ff3d4 100644 --- a/Marlin/src/HAL/ESP32/eeprom_impl.cpp +++ b/Marlin/src/HAL/ESP32/eeprom_impl.cpp @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) +#if USE_WIRED_EEPROM #include "../shared/eeprom_api.h" #include @@ -59,5 +59,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return EEPROM_SIZE; } -#endif // EEPROM_SETTINGS +#endif // USE_WIRED_EEPROM #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h index 11603c9ef4..8849c06e93 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h @@ -21,7 +21,7 @@ */ #pragma once -// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) - #define SDCARD_EEPROM_EMULATION +#undef USE_WIRED_EEPROM +#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) + #define USE_WIRED_EEPROM 1 #endif From 9f86dde19525af511b07239c23d93d586a045122 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 01:22:48 -0500 Subject: [PATCH 0094/1454] Clean up UI declarations, apply TERN_ --- Marlin/src/MarlinCore.cpp | 38 ++++++++++++++++++++------------------ Marlin/src/MarlinCore.h | 16 +++------------- Marlin/src/lcd/ultralcd.h | 23 +++++++++++++---------- 3 files changed, 36 insertions(+), 41 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 8130affe30..3a6582bbb1 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -218,13 +218,8 @@ bool wait_for_heatup = true; KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; if (ms) ms += millis(); // expire time - while (wait_for_user && !(ms && ELAPSED(millis(), ms))) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - no_sleep - #endif - ); - } + while (wait_for_user && !(ms && ELAPSED(millis(), ms))) + idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep)); wait_for_user = false; } @@ -647,52 +642,54 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { /** * Standard idle routine keeps the machine alive */ -void idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - bool no_stepper_sleep/*=false*/ - #endif -) { +void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { + // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) recovery.outage(); #endif + // Run StallGuard endstop checks #if ENABLED(SPI_ENDSTOPS) if (endstops.tmc_spi_homing.any - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - && ELAPSED(millis(), sg_guard_period) - #endif - ) { - for (uint8_t i = 4; i--;) // Read SGT 4 times per idle loop + && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period)) + ) LOOP_L_N(i, 4) // Read SGT 4 times per idle loop if (endstops.tmc_spi_homing_check()) break; - } #endif + // Max7219 heartbeat, animation, etc. #if ENABLED(MAX7219_DEBUG) max7219.idle_tasks(); #endif + // Read Buttons and Update the LCD ui.update(); + // Announce Host Keepalive state (if any) #if ENABLED(HOST_KEEPALIVE_FEATURE) gcode.host_keepalive(); #endif + // Core Marlin activities manage_inactivity( #if ENABLED(ADVANCED_PAUSE_FEATURE) no_stepper_sleep #endif ); + // Manage heaters (and Watchdog) thermalManager.manage_heater(); + // Update the Print Job Timer state #if ENABLED(PRINTCOUNTER) print_job_timer.tick(); #endif + // Update the Beeper queue #if USE_BEEPER buzzer.tick(); #endif + // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) static millis_t i2cpem_next_update_ms; if (planner.has_blocks_queued()) { @@ -704,10 +701,12 @@ void idle( } #endif + // Run HAL idle tasks #ifdef HAL_IDLETASK HAL_idletask(); #endif + // Auto-report Temperatures / SD Status #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { #if ENABLED(AUTO_REPORT_TEMPERATURES) @@ -719,14 +718,17 @@ void idle( } #endif + // Handle USB Flash Drive insert / remove #if ENABLED(USB_FLASH_DRIVE_SUPPORT) Sd2Card::idle(); #endif + // Update the Prusa MMU2 #if ENABLED(PRUSA_MMU2) mmu2.mmu_loop(); #endif + // Handle Joystick jogging #if ENABLED(POLL_JOG) joystick.inject_jog_moves(); #endif diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index e6678c5b18..3f8b72b88a 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -38,19 +38,9 @@ void stop(); -void idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - bool no_stepper_sleep=false // Pass true to keep steppers from timing out - #endif -); - -inline void idle_no_sleep() { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); -} +// Pass true to keep steppers from timing out +void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false)); +inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); } #if ENABLED(EXPERIMENTAL_I2CBUS) #include "feature/twibus.h" diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 1bcf9956fe..2737a1a648 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -273,7 +273,16 @@ public: // LCD implementations static void clear_lcd(); - static void init_lcd(); + + #if HAS_SPI_LCD + static bool detected(); + static void init_lcd(); + FORCE_INLINE static void refresh() { refresh(LCDVIEW_CLEAR_CALL_REDRAW); } + #else + static inline bool detected() { return true; } + static inline void init_lcd() {} + static inline void refresh() {} + #endif #if HAS_DISPLAY @@ -332,12 +341,9 @@ public: static millis_t next_button_update_ms; - static bool detected(); - static LCDViewAction lcdDrawUpdate; FORCE_INLINE static bool should_draw() { return bool(lcdDrawUpdate); } FORCE_INLINE static void refresh(const LCDViewAction type) { lcdDrawUpdate = type; } - FORCE_INLINE static void refresh() { refresh(LCDVIEW_CLEAR_CALL_REDRAW); } #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) static void draw_custom_bootscreen(const uint8_t frame=0); @@ -403,8 +409,6 @@ public: static void status_screen(); - #else - static void refresh() {} #endif static bool get_blink(); @@ -418,13 +422,12 @@ public: #else // No LCD // Send status to host as a notification - void set_status(const char* message, const bool=false); - void set_status_P(PGM_P message, const int8_t=0); - void status_printf_P(const uint8_t, PGM_P message, ...); + static void set_status(const char* message, const bool=false); + static void set_status_P(PGM_P message, const int8_t=0); + static void status_printf_P(const uint8_t, PGM_P message, ...); static inline void init() {} static inline void update() {} - static inline void refresh() {} static inline void return_to_status() {} static inline void set_alert_status_P(PGM_P const) {} static inline void reset_status(const bool=false) {} From 11ce281694c08565e14023f379f72e4765738442 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 13:32:49 -0500 Subject: [PATCH 0095/1454] Followup to #17351 --- Marlin/src/module/stepper/trinamic.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index f0ac48f514..1440c24cf8 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -341,7 +341,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; ptr[a] = p; return false; }; } sp_helper; - #define HW_SERIAL_BEGIN(A) do{ if (sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ + #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) #if AXIS_HAS_UART(X) #ifdef X_HARDWARE_SERIAL From be0e313c078c7425de7bc45a0371756ee2571056 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Thu, 2 Apr 2020 13:24:55 -0600 Subject: [PATCH 0096/1454] Touch UI additions, bug fixes (#17379) --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 + Marlin/src/feature/pause.cpp | 12 +- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 7 +- .../screens/bed_mesh_screen.cpp | 268 ++++++++++++++++++ .../ftdi_eve_touch_ui/screens/main_menu.cpp | 20 +- .../ftdi_eve_touch_ui/screens/screen_data.h | 6 + .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 3 + .../lib/ftdi_eve_touch_ui/screens/screens.h | 30 ++ Marlin/src/lcd/extui/ui_api.cpp | 14 +- Marlin/src/lcd/extui/ui_api.h | 4 + Marlin/src/lcd/extui_dgus_lcd.cpp | 4 + Marlin/src/lcd/extui_example.cpp | 4 + Marlin/src/lcd/language/language_en.h | 6 +- 13 files changed, 364 insertions(+), 18 deletions(-) create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 217d894543..940b4eaeb4 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -776,12 +776,16 @@ : find_closest_mesh_point_of_type(INVALID, near, true); if (best.pos.x >= 0) { // mesh point found and is reachable by probe + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_START); + #endif const float measured_z = probe.probe_at_point( best.meshpos(), stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level ); z_values[best.pos.x][best.pos.y] = measured_z; #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_FINISH); ExtUI::onMeshUpdate(best.pos, measured_z); #endif } diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 9c615b6ff8..23fa2fee01 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -499,10 +499,10 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR); + host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_NOZZLE_PARKED), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked")); + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED)); #endif wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { @@ -523,20 +523,20 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("HeaterTimeout"), PSTR("Reheat")); + host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT)); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout")); + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT)); #endif wait_for_user_response(0, true); // Wait for LCD click or M108 #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_INFO, PSTR("Reheating")); + host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING)); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onStatusChanged(PSTR("Reheating...")); + ExtUI::onStatusChanged(GET_TEXT(MSG_REHEATING)); #endif // Re-enable the heaters if they timed out diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index bed32cc606..9271f2a0cd 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -127,7 +127,12 @@ namespace ExtUI { } #if HAS_LEVELING && HAS_MESH - void onMeshUpdate(const int8_t, const int8_t, const float) { + void onMeshUpdate(const int8_t x, const int8_t y, const float val) { + BedMeshScreen::onMeshUpdate(x, y, val); + } + + void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { + BedMeshScreen::onMeshUpdate(x, y, state); } #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp new file mode 100644 index 0000000000..bce39a6ec0 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -0,0 +1,268 @@ +/*********************** + * bed_mesh_screen.cpp * + ***********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" + +#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_MESH + +#include "screens.h" +#include "screen_data.h" + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +#ifdef TOUCH_UI_PORTRAIT + #define GRID_COLS 2 + #define GRID_ROWS 10 + + #define MESH_POS BTN_POS(1, 2), BTN_SIZE(2,5) + #define Z_LABEL_POS BTN_POS(1, 8), BTN_SIZE(1,1) + #define Z_VALUE_POS BTN_POS(2, 8), BTN_SIZE(1,1) + #define WAIT_POS BTN_POS(1, 8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,10), BTN_SIZE(2,1) +#else + #define GRID_COLS 5 + #define GRID_ROWS 5 + + #define MESH_POS BTN_POS(2,1), BTN_SIZE(4,5) + #define Z_LABEL_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define Z_VALUE_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define WAIT_POS BTN_POS(1,3), BTN_SIZE(2,2) + #define BACK_POS BTN_POS(1,5), BTN_SIZE(2,1) +#endif + +void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts) { + CommandProcessor cmd; + + #define TRANSFORM_2(X,Y,Z) (X), (Y) // No transform + #define TRANSFORM_1(X,Y,Z) TRANSFORM_2((X) + (Y) * slant, (Y) - (Z), 0) // Perspective + #define TRANSFORM(X,Y,Z) TRANSFORM_1(float(X)/(cols-1) - 0.5, float(Y)/(rows-1) - 0.5, (Z)) // Normalize + + constexpr uint8_t rows = GRID_MAX_POINTS_Y; + constexpr uint8_t cols = GRID_MAX_POINTS_X; + const float slant = 0.5; + const float bounds_min[] = {TRANSFORM(0 ,0 ,0)}; + const float bounds_max[] = {TRANSFORM(cols,rows,0)}; + const float scale_x = float(w)/(bounds_max[0] - bounds_min[0]); + const float scale_y = float(h)/(bounds_max[1] - bounds_min[1]); + const float center_x = x + w/2; + const float center_y = y + h/2; + + float val_mean = 0; + float val_max = -INFINITY; + float val_min = INFINITY; + uint8_t val_cnt = 0; + + if (opts & USE_AUTOSCALE) { + // Compute the mean + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + const float val = data[x][y]; + if (!isnan(val)) { + val_mean += val; + val_max = max(val_max, val); + val_min = min(val_min, val); + val_cnt++; + } + } + } + if (val_cnt) { + val_mean /= val_cnt; + val_min -= val_mean; + val_max -= val_mean; + } else { + val_mean = 0; + val_min = 0; + val_max = 0; + } + } + + const float scale_z = ((val_max == val_min) ? 1 : 1/(val_max - val_min)) * 0.1; + + #undef TRANSFORM_2 + #define TRANSFORM_2(X,Y,Z) center_x + (X) * scale_x, center_y + (Y) * scale_y // Scale and position + #define VALUE(X,Y) ((data && ISVAL(X,Y)) ? data[X][Y] : 0) + #define ISVAL(X,Y) (data ? !isnan(data[X][Y]) : true) + #define HEIGHT(X,Y) (VALUE(X,Y) * scale_z) + + uint16_t basePointSize = min(scale_x,scale_y) / max(cols,rows); + + cmd.cmd(SAVE_CONTEXT()) + .cmd(VERTEX_FORMAT(0)) + .cmd(TAG_MASK(false)) + .cmd(SAVE_CONTEXT()); + + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + const bool hasLeftSegment = x < cols - 1 && ISVAL(x+1,y); + const bool hasRightSegment = y < rows - 1 && ISVAL(x,y+1); + if (hasLeftSegment || hasRightSegment) { + cmd.cmd(BEGIN(LINE_STRIP)); + if (hasLeftSegment) cmd.cmd(VERTEX2F(TRANSFORM(x + 1, y , HEIGHT(x + 1, y )))); + cmd.cmd( VERTEX2F(TRANSFORM(x , y , HEIGHT(x , y )))); + if (hasRightSegment) cmd.cmd(VERTEX2F(TRANSFORM(x , y + 1, HEIGHT(x , y + 1)))); + } + } + } + + if (opts & USE_POINTS) { + cmd.cmd(POINT_SIZE(basePointSize * 2)); + cmd.cmd(BEGIN(POINTS)); + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + if (opts & USE_COLORS) { + const float val_dev = VALUE(x, y) - val_mean; + const uint8_t neg_byte = sq(val_dev) / sq(val_dev < 0 ? val_min : val_max) * 0xFF; + const uint8_t pos_byte = 255 - neg_byte; + cmd.cmd(COLOR_RGB(pos_byte, pos_byte, 0xFF)); + } + cmd.cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + } + if (opts & USE_COLORS) { + cmd.cmd(RESTORE_CONTEXT()) + .cmd(SAVE_CONTEXT()); + } + } + } + cmd.cmd(RESTORE_CONTEXT()) + .cmd(TAG_MASK(true)); + + if (opts & USE_TAGS) { + cmd.cmd(COLOR_MASK(false, false, false, false)) + .cmd(POINT_SIZE(basePointSize * 10)) + .cmd(BEGIN(POINTS)); + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + const uint8_t tag = pointToTag(x, y); + cmd.tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + } + cmd.cmd(COLOR_MASK(true, true, true, true)); + } + + if (opts & USE_HIGHLIGHT) { + const uint8_t tag = screen_data.BedMeshScreen.highlightedTag; + uint8_t x, y; + tagToPoint(tag, x, y); + cmd.cmd(COLOR_A(128)) + .cmd(POINT_SIZE(basePointSize * 6)) + .cmd(BEGIN(POINTS)) + .tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + cmd.cmd(END()); + cmd.cmd(RESTORE_CONTEXT()); +} + +uint8_t BedMeshScreen::pointToTag(uint8_t x, uint8_t y) { + return y * (GRID_MAX_POINTS_X) + x + 10; +} + +void BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { + x = (tag - 10) % (GRID_MAX_POINTS_X); + y = (tag - 10) / (GRID_MAX_POINTS_X); +} + +void BedMeshScreen::onEntry() { + screen_data.BedMeshScreen.highlightedTag = 0; + screen_data.BedMeshScreen.count = 0; + BaseScreen::onEntry(); +} + +float BedMeshScreen::getHightlightedValue() { + if (screen_data.BedMeshScreen.highlightedTag) { + xy_uint8_t pt; + tagToPoint(screen_data.BedMeshScreen.highlightedTag, pt.x, pt.y); + return ExtUI::getMeshPoint(pt); + } + return NAN; +} + +void BedMeshScreen::drawHighlightedPointValue() { + char str[16]; + const float val = getHightlightedValue(); + const bool isGood = !isnan(val); + if (isGood) + dtostrf(val, 5, 3, str); + else + strcpy_P(str, PSTR("-")); + + CommandProcessor cmd; + cmd.font(Theme::font_medium) + .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) + .text(Z_VALUE_POS, str) + .colors(action_btn) + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)) + .tag(0); +} + +void BedMeshScreen::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + + // Draw the shadow and tags + cmd.cmd(COLOR_RGB(0x444444)); + BedMeshScreen::drawMesh(MESH_POS, nullptr, USE_POINTS | USE_TAGS); + cmd.cmd(COLOR_RGB(bg_text_enabled)); + } + + if (what & FOREGROUND) { + const bool levelingFinished = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; + if (levelingFinished) drawHighlightedPointValue(); + + BedMeshScreen::drawMesh(MESH_POS, ExtUI::getMeshArray(), + USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0)); + } +} + +bool BedMeshScreen::onTouchStart(uint8_t tag) { + screen_data.BedMeshScreen.highlightedTag = tag; + return true; +} + +bool BedMeshScreen::onTouchEnd(uint8_t tag) { + switch(tag) { + case 1: + GOTO_PREVIOUS(); + return true; + default: + return false; + } +} + +void BedMeshScreen::onMeshUpdate(const int8_t, const int8_t, const float) { + if (AT_SCREEN(BedMeshScreen)) + onRefresh(); +} + +void BedMeshScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { + if (state == ExtUI::PROBE_FINISH) { + screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); + screen_data.BedMeshScreen.count++; + } + BedMeshScreen::onMeshUpdate(x, y, 0); +} + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp index 5d165edef0..5a81a48257 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -146,14 +146,18 @@ bool MainMenu::onTouchEnd(uint8_t tag) { #ifdef AXIS_LEVELING_COMMANDS case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; #endif - #ifdef HAS_LEVELING - case 10: SpinnerDialogBox::enqueueAndWait_P(F( - #ifdef BED_LEVELING_COMMANDS - BED_LEVELING_COMMANDS - #else - "G29" - #endif - )); break; + #if HAS_LEVELING + case 10: + #ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" + #endif + #if HAS_MESH + GOTO_SCREEN(BedMeshScreen); + injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); + #else + SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); + #endif + break; #endif case 11: GOTO_SCREEN(AboutScreen); break; default: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h index 6e2cb97a98..a0bc60d488 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h @@ -60,6 +60,12 @@ union screen_data_t { struct base_numeric_adjustment_t placeholder; float e_rel[ExtUI::extruderCount]; } MoveAxisScreen; +#if HAS_MESH + struct { + uint8_t count; + uint8_t highlightedTag; + } BedMeshScreen; +#endif #if ENABLED(TOUCH_UI_DEVELOPER_MENU) struct { uint32_t next_watchdog_trigger; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index ce75462040..5f59843bbe 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -55,6 +55,9 @@ SCREEN_TABLE { #endif #if ENABLED(BABYSTEPPING) DECL_SCREEN(NudgeNozzleScreen), +#endif +#if HAS_MESH + DECL_SCREEN(BedMeshScreen), #endif DECL_SCREEN(MoveAxisScreen), DECL_SCREEN(StepsScreen), diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 346d122a0f..8fa4800d6a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -55,6 +55,9 @@ enum { MAX_VELOCITY_SCREEN_CACHE, MAX_ACCELERATION_SCREEN_CACHE, DEFAULT_ACCELERATION_SCREEN_CACHE, +#if HAS_MESH + BED_MESH_SCREEN_CACHE, +#endif #if DISABLED(CLASSIC_JERK) JUNC_DEV_SCREEN_CACHE, #else @@ -130,6 +133,33 @@ class AboutScreen : public BaseScreen, public UncachedScreen { static bool onTouchEnd(uint8_t tag); }; +#if HAS_MESH +class BedMeshScreen : public BaseScreen, public CachedScreen { + private: + enum MeshOpts { + USE_POINTS = 0x01, + USE_COLORS = 0x02, + USE_TAGS = 0x04, + USE_HIGHLIGHT = 0x08, + USE_AUTOSCALE = 0x10 + }; + + static uint8_t pointToTag(uint8_t x, uint8_t y); + static void tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y); + static float getHightlightedValue(); + static void drawHighlightedPointValue(); + static void drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts); + + public: + static void onMeshUpdate(const int8_t x, const int8_t y, const float val); + static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchStart(uint8_t tag); + static bool onTouchEnd(uint8_t tag); +}; +#endif + #if ENABLED(PRINTCOUNTER) class StatisticsScreen : public BaseScreen, public UncachedScreen { public: diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 79e12f36d1..a5b1460c90 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -112,6 +112,9 @@ namespace ExtUI { #if ENABLED(JOYSTICK) uint8_t jogging : 1; #endif + #if ENABLED(SDSUPPORT) + uint8_t was_sd_printing : 1; + #endif } flags; #ifdef __SAM3X8E__ @@ -1032,11 +1035,18 @@ namespace ExtUI { } bool isPrintingFromMedia() { - return IFSD(card.isFileOpen(), false); + #if ENABLED(SDSUPPORT) + // Account for when IS_SD_PRINTING() reports the end of the + // print when there is still SD card data in the planner. + flags.was_sd_printing = card.isFileOpen() || (flags.was_sd_printing && commandsInQueue()); + return flags.was_sd_printing; + #else + return false; + #endif } bool isPrinting() { - return (planner.movesplanned() || isPrintingFromMedia() || IFSD(IS_SD_PRINTING(), false)); + return (commandsInQueue() || isPrintingFromMedia() || IFSD(IS_SD_PRINTING(), false)); } bool isMediaInserted() { diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 01e0d1b7a3..43e337e877 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -141,6 +141,10 @@ namespace ExtUI { void setMeshPoint(const xy_uint8_t &pos, const float zval); void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); inline void onMeshUpdate(const xy_int8_t &pos, const float zval) { onMeshUpdate(pos.x, pos.y, zval); } + + typedef enum : unsigned char { PROBE_START, PROBE_FINISH } probe_state_t; + void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state); + inline void onMeshUpdate(const xy_int8_t &pos, probe_state_t state) { onMeshUpdate(pos.x, pos.y, state); } #endif #endif diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 855d09033e..8880be7ef3 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -122,6 +122,10 @@ namespace ExtUI { // Called when any mesh points are updated } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() { // Called on resume from power-loss diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 5c9a193ded..900afdea04 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -93,6 +93,10 @@ namespace ExtUI { // Called when any mesh points are updated } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() { // Called on resume from power-loss diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index a52d9652ac..79a6f814b2 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -240,6 +240,8 @@ namespace Language_en { PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Bed"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Enclosure"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fan Speed"); @@ -371,7 +373,6 @@ namespace Language_en { PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Raise"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prime Speed"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Retract Speed"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Change Filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Change Filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Load Filament"); @@ -605,6 +606,9 @@ namespace Language_en { PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); } #if FAN_COUNT == 1 From 2b9d2dce16dac5be0e489f2bc74be6555e245763 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 14:32:49 -0500 Subject: [PATCH 0097/1454] Apply GRID_LOOP --- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 15 +++++++------ Marlin/src/gcode/bedlevel/M420.cpp | 28 +++++++++++-------------- 2 files changed, 19 insertions(+), 24 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 8ef2ad564c..cf8e935be9 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -49,14 +49,13 @@ void unified_bed_leveling::report_current_mesh() { if (!leveling_is_valid()) return; SERIAL_ECHO_MSG(" G29 I99"); - LOOP_L_N(x, GRID_MAX_POINTS_X) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(z_values[x][y])) { - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y)); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); - serial_delay(75); // Prevent Printrun from exploding - } + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y)); + SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); + serial_delay(75); // Prevent Printrun from exploding + } } void unified_bed_leveling::report_state() { diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index d042ace8da..ad2e01f093 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -155,21 +155,18 @@ void GcodeSuite::M420() { // Get the sum and average of all mesh values float mesh_sum = 0; - for (uint8_t x = GRID_MAX_POINTS_X; x--;) - for (uint8_t y = GRID_MAX_POINTS_Y; y--;) - mesh_sum += Z_VALUES(x, y); + GRID_LOOP(x, y) mesh_sum += Z_VALUES(x, y); const float zmean = mesh_sum / float(GRID_MAX_POINTS); #else // Find the low and high mesh values float lo_val = 100, hi_val = -100; - for (uint8_t x = GRID_MAX_POINTS_X; x--;) - for (uint8_t y = GRID_MAX_POINTS_Y; y--;) { - const float z = Z_VALUES(x, y); - NOMORE(lo_val, z); - NOLESS(hi_val, z); - } + GRID_LOOP(x, y) { + const float z = Z_VALUES(x, y); + NOMORE(lo_val, z); + NOLESS(hi_val, z); + } // Take the mean of the lowest and highest const float zmean = (lo_val + hi_val) / 2.0 + cval; @@ -179,13 +176,12 @@ void GcodeSuite::M420() { if (!NEAR_ZERO(zmean)) { set_bed_leveling_enabled(false); // Subtract the mean from all values - for (uint8_t x = GRID_MAX_POINTS_X; x--;) - for (uint8_t y = GRID_MAX_POINTS_Y; y--;) { - Z_VALUES(x, y) -= zmean; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); - #endif - } + GRID_LOOP(x, y) { + Z_VALUES(x, y) -= zmean; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); + #endif + } #if ENABLED(ABL_BILINEAR_SUBDIVISION) bed_level_virt_interpolate(); #endif From e7e9304819f659cfd09d82597fc6ded871df405c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 3 Apr 2020 00:03:31 +0000 Subject: [PATCH 0098/1454] [cron] Bump distribution date (2020-04-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0316c69672..fce0c46b5c 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-02" + #define STRING_DISTRIBUTION_DATE "2020-04-03" #endif /** From df8b7dfc406be095a62b5445b69c40034d418823 Mon Sep 17 00:00:00 2001 From: Ben Date: Fri, 3 Apr 2020 01:31:08 +0100 Subject: [PATCH 0099/1454] Various Laser / Spindle improvements (#15335) --- Marlin/Configuration_adv.h | 122 ++++++++++++-- Marlin/src/HAL/AVR/HAL.h | 2 + Marlin/src/HAL/AVR/fast_pwm.cpp | 4 +- Marlin/src/HAL/LPC1768/HAL.h | 2 + Marlin/src/HAL/LPC1768/fast_pwm.cpp | 2 +- Marlin/src/MarlinCore.cpp | 22 ++- Marlin/src/core/drivers.h | 9 - Marlin/src/feature/spindle_laser.cpp | 49 +++--- Marlin/src/feature/spindle_laser.h | 145 ++++++++++++---- Marlin/src/feature/spindle_laser_types.h | 50 ++++++ Marlin/src/gcode/control/M3-M5.cpp | 41 ++++- Marlin/src/gcode/gcode.cpp | 16 ++ Marlin/src/gcode/motion/G0_G1.cpp | 2 +- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- Marlin/src/inc/Conditionals_adv.h | 32 +++- Marlin/src/inc/Conditionals_post.h | 48 +++--- Marlin/src/inc/SanityCheck.h | 51 +++++- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 8 +- Marlin/src/lcd/language/language_en.h | 3 +- Marlin/src/lcd/menu/menu_spindle_laser.cpp | 21 ++- Marlin/src/module/planner.cpp | 54 +++++- Marlin/src/module/planner.h | 46 ++++- Marlin/src/module/stepper.cpp | 186 ++++++++++++++++++--- Marlin/src/module/stepper.h | 28 +++- 24 files changed, 776 insertions(+), 169 deletions(-) create mode 100644 Marlin/src/feature/spindle_laser_types.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 00f89662c7..7d1547c0d0 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2662,31 +2662,123 @@ #define SPINDLE_LASER_ACTIVE_HIGH false // Set to "true" if the on/off function is active HIGH #define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power #define SPINDLE_LASER_PWM_INVERT true // Set to "true" if the speed/power goes up when you want it to go slower - #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power - #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop + + #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) + + /** + * Speed / Power can be set ('M3 S') and displayed in terms of: + * - PWM (S0 - S255) + * - PERCENT (S0 - S100) + * - RPM (S0 - S50000) Best for use with a spindle + */ + #define CUTTER_POWER_DISPLAY PWM + + /** + * Relative mode uses relative range (SPEED_POWER_MIN to SPEED_POWER_MAX) instead of normal range (0 to SPEED_POWER_MAX) + * Best use with SuperPID router controller where for example S0 = 5,000 RPM and S255 = 30,000 RPM + */ + //#define CUTTER_POWER_RELATIVE // Set speed proportional to [SPEED_POWER_MIN...SPEED_POWER_MAX] instead of directly #if ENABLED(SPINDLE_FEATURE) //#define SPINDLE_CHANGE_DIR // Enable if your spindle controller can change spindle direction #define SPINDLE_CHANGE_DIR_STOP // Enable if the spindle should stop before changing spin direction #define SPINDLE_INVERT_DIR false // Set to "true" if the spin direction is reversed + #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop + /** - * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * M3/M4 uses the following equation to convert speed/power to PWM duty cycle + * Power = ((DC / 255 * 100) - SPEED_POWER_INTERCEPT)) * (1 / SPEED_POWER_SLOPE) + * where PWM DC varies from 0 to 255 * - * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT - * where PWM duty cycle varies from 0 to 255 - * - * set the following for your controller (ALL MUST BE SET) + * Set these required parameters for your controller */ - #define SPEED_POWER_SLOPE 118.4 - #define SPEED_POWER_INTERCEPT 0 - #define SPEED_POWER_MIN 5000 - #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_SLOPE 118.4 // SPEED_POWER_SLOPE = SPEED_POWER_MAX / 255 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_STARTUP 25000 // The default value for speed power when M3 is called without arguments + #else - #define SPEED_POWER_SLOPE 0.3922 - #define SPEED_POWER_INTERCEPT 0 - #define SPEED_POWER_MIN 10 - #define SPEED_POWER_MAX 100 // 0-100% + + #define SPEED_POWER_SLOPE 0.3922 // SPEED_POWER_SLOPE = SPEED_POWER_MAX / 255 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 0 + #define SPEED_POWER_MAX 100 // 0-100% + #define SPEED_POWER_STARTUP 80 // The default value for speed power when M3 is called without arguments + + /** + * Enable inline laser power to be handled in the planner / stepper routines. + * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) + * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER). + * + * This allows the laser to keep in perfect sync with the planner and removes + * the powerup/down delay since lasers require negligible time. + */ + #define LASER_POWER_INLINE + + #if ENABLED(LASER_POWER_INLINE) + /** + * Scale the laser's power in proportion to the movement rate. + * + * - Sets the entry power proportional to the entry speed over the nominal speed. + * - Ramps the power up every N steps to approximate the speed trapezoid. + * - Due to the limited power resolution this is only approximate. + */ + #define LASER_POWER_INLINE_TRAPEZOID + + /** + * Continuously calculate the current power (nominal_power * current_rate / nominal_rate). + * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION). + * This is a costly calculation so this option is discouraged on 8-bit AVR boards. + * + * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your + * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this. + * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT + + /** + * Stepper iterations between power updates. Increase this value if the board + * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT. + * Disable (or set to 0) to recalculate power on every stepper iteration. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10 + + /** + * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter + */ + //#define LASER_MOVE_POWER + + #if ENABLED(LASER_MOVE_POWER) + // Turn off the laser on G0 moves with no power parameter. + // If a power parameter is provided, use that instead. + //#define LASER_MOVE_G0_OFF + #endif + + /** + * Inline flag inverted + * + * WARNING: M5 will NOT turn off the laser unless another move + * is done (so G-code files must end with 'M5 I'). + */ + //#define LASER_POWER_INLINE_INVERT + + /** + * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I') + * + * The laser might do some weird things, so only enable this + * feature if you understand the implications. + */ + //#define LASER_POWER_INLINE_CONTINUOUS + + #else + + #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop + + #endif #endif #endif diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 0255169819..f715295d0a 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -395,6 +395,8 @@ inline void HAL_adc_init() { // AVR compatibility #define strtof strtod +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + /** * set_pwm_frequency * Sets the frequency of the timer corresponding to the provided pin diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 42e7cc3f10..e855057486 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM #include "HAL.h" @@ -278,5 +278,5 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } } -#endif // FAST_PWM_FAN || SPINDLE_LASER_PWM +#endif // NEEDS_HARDWARE_PWM #endif // __AVR__ diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index f5ea629f16..70bb50e692 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -197,6 +197,8 @@ void HAL_idletask(); #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + /** * set_pwm_frequency * Set the frequency of the timer corresponding to the provided pin diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index a1feb25903..4f2e30ee72 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM #include diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 3a6582bbb1..5073c339cd 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -420,7 +420,11 @@ void startOrResumeJob() { #if DISABLED(SD_ABORT_NO_COOLDOWN) thermalManager.disable_all_heaters(); #endif - thermalManager.zero_fan_speeds(); + #if !HAS_CUTTER + thermalManager.zero_fan_speeds(); + #else + cutter.kill(); // Full cutter shutdown including ISR control + #endif wait_for_heatup = false; #if ENABLED(POWER_LOSS_RECOVERY) recovery.purge(); @@ -741,6 +745,10 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { thermalManager.disable_all_heaters(); + #if HAS_CUTTER + cutter.kill(); // Full cutter shutdown including ISR control + #endif + SERIAL_ERROR_MSG(STR_ERR_KILLED); #if HAS_DISPLAY @@ -770,6 +778,10 @@ void minkill(const bool steppers_off/*=false*/) { // Reiterate heaters off thermalManager.disable_all_heaters(); + #if HAS_CUTTER + cutter.kill(); // Reiterate cutter shutdown + #endif + // Power off all steppers (for M112) or just the E steppers steppers_off ? disable_all_steppers() : disable_e_steppers(); @@ -789,14 +801,14 @@ void minkill(const bool steppers_off/*=false*/) { // Wait for kill to be pressed while (READ(KILL_PIN)) watchdog_refresh(); - void (*resetFunc)() = 0; // Declare resetFunc() at address 0 + void (*resetFunc)() = 0; // Declare resetFunc() at address 0 resetFunc(); // Jump to address 0 - #else // !HAS_KILL + #else - for (;;) watchdog_refresh(); // Wait for reset + for (;;) watchdog_refresh(); // Wait for reset - #endif // !HAS_KILL + #endif } /** diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 833899bdcb..418a24ec92 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -174,15 +174,6 @@ // Defines that can't be evaluated now #define HAS_TMC_SW_SERIAL ANY_AXIS_HAS(SW_SERIAL) -// -// Stretching 'drivers.h' to include LPC/SAMD51 SD options -// -#define _SDCARD_LCD 1 -#define _SDCARD_ONBOARD 2 -#define _SDCARD_CUSTOM_CABLE 3 -#define _SDCARD_ID(V) _CAT(_SDCARD_, V) -#define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V)) - #if HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01) #define HAS_L64XX 1 #endif diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 0567ba5d3e..63c9891109 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -32,10 +32,17 @@ SpindleLaser cutter; -cutter_power_t SpindleLaser::power; // = 0 - +cutter_power_t SpindleLaser::power; +bool SpindleLaser::isOn; // state to determine when to apply setPower to power +cutter_setPower_t SpindleLaser::setPower = interpret_power(SPEED_POWER_MIN); // spindle/laser speed/power control in PWM, Percentage or RPM +#if ENABLED(MARLIN_DEV_MODE) + cutter_frequency_t SpindleLaser::frequency; // setting PWM frequency; range: 2K - 50K +#endif #define SPINDLE_LASER_PWM_OFF ((SPINDLE_LASER_PWM_INVERT) ? 255 : 0) +// +// Init the cutter to a safe OFF state +// void SpindleLaser::init() { OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Init spindle to off #if ENABLED(SPINDLE_CHANGE_DIR) @@ -45,41 +52,39 @@ void SpindleLaser::init() { SET_PWM(SPINDLE_LASER_PWM_PIN); analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // set to lowest speed #endif + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + #if ENABLED(MARLIN_DEV_MODE) + frequency = SPINDLE_LASER_FREQUENCY; + #endif + #endif } #if ENABLED(SPINDLE_LASER_PWM) /** - * ocr_val_mode() is used for debugging and to get the points needed to compute the RPM vs ocr_val line - * - * it accepts inputs of 0-255 - */ + * Set the cutter PWM directly to the given ocr value + **/ void SpindleLaser::set_ocr(const uint8_t ocr) { - WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low) + WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } #endif +// +// Set cutter ON state (and PWM) to the given cutter power value +// void SpindleLaser::apply_power(const cutter_power_t inpow) { static cutter_power_t last_power_applied = 0; if (inpow == last_power_applied) return; last_power_applied = inpow; #if ENABLED(SPINDLE_LASER_PWM) - if (enabled()) { - #define _scaled(F) ((F - (SPEED_POWER_INTERCEPT)) * inv_slope) - constexpr float inv_slope = RECIPROCAL(SPEED_POWER_SLOPE), - min_ocr = _scaled(SPEED_POWER_MIN), - max_ocr = _scaled(SPEED_POWER_MAX); - int16_t ocr_val; - if (inpow <= SPEED_POWER_MIN) ocr_val = min_ocr; // Use minimum if set below - else if (inpow >= SPEED_POWER_MAX) ocr_val = max_ocr; // Use maximum if set above - else ocr_val = _scaled(inpow); // Use calculated OCR value - set_ocr(ocr_val & 0xFF); // ...limited to Atmel PWM max - } + if (enabled()) + set_ocr(translate_power(inpow)); else { - WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off (active low) - analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte + WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off + analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte } #else WRITE(SPINDLE_LASER_ENA_PIN, (SPINDLE_LASER_ACTIVE_HIGH) ? enabled() : !enabled()); @@ -88,6 +93,10 @@ void SpindleLaser::apply_power(const cutter_power_t inpow) { #if ENABLED(SPINDLE_CHANGE_DIR) + // + // Set the spindle direction and apply immediately + // Stop on direction change if SPINDLE_STOP_ON_DIR_CHANGE is enabled + // void SpindleLaser::set_direction(const bool reverse) { const bool dir_state = (reverse == SPINDLE_INVERT_DIR); // Forward (M3) HIGH when not inverted #if ENABLED(SPINDLE_STOP_ON_DIR_CHANGE) diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index ea035299be..3d7ab6c360 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -28,55 +28,98 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SPINDLE_FEATURE) - #define _MSG_CUTTER(M) MSG_SPINDLE_##M -#else - #define _MSG_CUTTER(M) MSG_LASER_##M -#endif -#define MSG_CUTTER(M) _MSG_CUTTER(M) +#include "spindle_laser_types.h" -#if SPEED_POWER_MAX > 255 - typedef uint16_t cutter_power_t; - #define CUTTER_MENU_TYPE uint16_5 -#else - typedef uint8_t cutter_power_t; - #define CUTTER_MENU_TYPE uint8 +#if ENABLED(LASER_POWER_INLINE) + #include "../module/planner.h" #endif class SpindleLaser { public: + static bool isOn; // state to determine when to apply setPower to power static cutter_power_t power; - static inline uint8_t powerPercent(const uint8_t pp) { return ui8_to_percent(pp); } // for display + static cutter_setPower_t setPower; // spindle/laser menu set power; in PWM, Percentage or RPM + #if ENABLED(MARLIN_DEV_MODE) + static cutter_frequency_t frequency; // set PWM frequency; range: 2K-50K + #endif + + static cutter_setPower_t interpret_power(const float pwr) { // convert speed/power to configured PWM, Percentage or RPM in relative or normal range + #if CUTTER_DISPLAY_IS(PERCENT) + return (pwr / SPEED_POWER_MAX) * 100; // to percent + #elif CUTTER_DISPLAY_IS(RPM) // to RPM is unaltered + return pwr; + #else // to PWM + #if ENABLED(CUTTER_POWER_RELATIVE) + return (pwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) * 255; // using rpm range as relative percentage + #else + return (pwr / SPEED_POWER_MAX) * 255; + #endif + #endif + } + /** + * Translate speed/power --> percentage --> PWM value + **/ + static cutter_power_t translate_power(const float pwr) { + float pwrpc; + #if CUTTER_DISPLAY_IS(PERCENT) + pwrpc = pwr; + #elif CUTTER_DISPLAY_IS(RPM) // RPM to percent + #if ENABLED(CUTTER_POWER_RELATIVE) + pwrpc = (pwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) * 100; + #else + pwrpc = pwr / SPEED_POWER_MAX * 100; + #endif + #else + return pwr; // PWM + #endif + + #if ENABLED(SPINDLE_FEATURE) + #if ENABLED(CUTTER_POWER_RELATIVE) + constexpr float spmin = 0; + #else + constexpr float spmin = SPEED_POWER_MIN / SPEED_POWER_MAX * 100; // convert to percentage + #endif + constexpr float spmax = 100; + #else + constexpr float spmin = SPEED_POWER_MIN; + constexpr float spmax = SPEED_POWER_MAX; + #endif + + constexpr float inv_slope = RECIPROCAL(SPEED_POWER_SLOPE), + min_ocr = (spmin - (SPEED_POWER_INTERCEPT)) * inv_slope, // Minimum allowed + max_ocr = (spmax - (SPEED_POWER_INTERCEPT)) * inv_slope; // Maximum allowed + float ocr_val; + if (pwrpc < spmin) ocr_val = min_ocr; // Use minimum if set below + else if (pwrpc > spmax) ocr_val = max_ocr; // Use maximum if set above + else ocr_val = (pwrpc - (SPEED_POWER_INTERCEPT)) * inv_slope; // Use calculated OCR value + return ocr_val; // ...limited to Atmel PWM max + } static void init(); - static inline bool enabled() { return !!power; } - - static inline void set_power(const cutter_power_t pwr) { power = pwr; } - - static inline void refresh() { apply_power(power); } - - static inline void set_enabled(const bool enable) { - const bool was = enabled(); - set_power(enable ? 255 : 0); - if (was != enable) power_delay(); - } - + // Modifying this function should update everywhere + static inline bool enabled(const cutter_power_t pwr) { return pwr > 0; } + static inline bool enabled() { return enabled(power); } + #if ENABLED(MARLIN_DEV_MODE) + static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + #endif static void apply_power(const cutter_power_t inpow); - //static bool active() { return READ(SPINDLE_LASER_ENA_PIN) == SPINDLE_LASER_ACTIVE_HIGH; } + FORCE_INLINE static void refresh() { apply_power(power); } + FORCE_INLINE static void set_power(const cutter_power_t pwr) { power = pwr; refresh(); } - static void update_output(); + static inline void set_enabled(const bool enable) { set_power(enable ? (power ?: interpret_power(SPEED_POWER_STARTUP)) : 0); } #if ENABLED(SPINDLE_LASER_PWM) static void set_ocr(const uint8_t ocr); - static inline void set_ocr_power(const cutter_power_t pwr) { power = pwr; set_ocr(pwr); } + static inline void set_ocr_power(const uint8_t pwr) { power = pwr; set_ocr(pwr); } + // static uint8_t translate_power(const cutter_power_t pwr); // Used by update output for power->OCR translation #endif // Wait for spindle to spin up or spin down - static inline void power_delay() { - #if SPINDLE_LASER_POWERUP_DELAY || SPINDLE_LASER_POWERDOWN_DELAY - safe_delay(enabled() ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); + static inline void power_delay(const bool on) { + #if DISABLED(LASER_POWER_INLINE) + safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); #endif } @@ -86,10 +129,44 @@ public: static inline void set_direction(const bool) {} #endif - static inline void disable() { set_enabled(false); } - static inline void enable_forward() { set_direction(false); set_enabled(true); } - static inline void enable_reverse() { set_direction(true); set_enabled(true); } + static inline void disable() { isOn = false; set_enabled(false); } + #if HAS_LCD_MENU + static inline void enable_forward() { isOn = true; setPower ? (power = setPower) : (setPower = interpret_power(SPEED_POWER_STARTUP)); set_direction(false); set_enabled(true); } + static inline void enable_reverse() { isOn = true; setPower ? (power = setPower) : (setPower = interpret_power(SPEED_POWER_STARTUP)); set_direction(true); set_enabled(true); } + #endif + #if ENABLED(LASER_POWER_INLINE) + // Force disengage planner power control + static inline void inline_disable() { planner.settings.laser.status = 0; planner.settings.laser.power = 0; isOn = false;} + + // Inline modes of all other functions; all enable planner inline power control + static inline void inline_enabled(const bool enable) { enable ? inline_power(SPEED_POWER_STARTUP) : inline_ocr_power(0); } + + static void inline_power(const cutter_power_t pwr) { + #if ENABLED(SPINDLE_LASER_PWM) + inline_ocr_power(translate_power(pwr)); + #else + planner.settings.laser.status = enabled(pwr) ? 0x03 : 0x01; + planner.settings.laser.power = pwr; + #endif + } + + static inline void inline_direction(const bool reverse) { UNUSED(reverse); } // TODO is this ever going to be needed + + #if ENABLED(SPINDLE_LASER_PWM) + static inline void inline_ocr_power(const uint8_t pwr) { + planner.settings.laser.status = pwr ? 0x03 : 0x01; + planner.settings.laser.power = pwr; + } + #endif + #endif + + static inline void kill() { + #if ENABLED(LASER_POWER_INLINE) + inline_disable(); + #endif + disable(); + } }; extern SpindleLaser cutter; diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h new file mode 100644 index 0000000000..9e3f2bae48 --- /dev/null +++ b/Marlin/src/feature/spindle_laser_types.h @@ -0,0 +1,50 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * feature/spindle_laser_types.h + * Support for Laser Power or Spindle Power & Direction + */ + +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(SPINDLE_FEATURE) + #define _MSG_CUTTER(M) MSG_SPINDLE_##M +#else + #define _MSG_CUTTER(M) MSG_LASER_##M +#endif +#define MSG_CUTTER(M) _MSG_CUTTER(M) +#if CUTTER_DISPLAY_IS(RPM) && SPEED_POWER_MAX > 255 + #define cutter_power_t uint16_t + #define cutter_setPower_t uint16_t + #define CUTTER_MENU_POWER_TYPE uint16_5 +#else + #define cutter_power_t uint8_t + #define cutter_setPower_t uint8_t + #define CUTTER_MENU_POWER_TYPE uint8 +#endif + +#if ENABLED(MARLIN_DEV_MODE) + #define cutter_frequency_t uint16_t + #define CUTTER_MENU_FREQUENCY_TYPE uint16_5 +#endif diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 56e1e0e4ec..9c897abf01 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -28,6 +28,12 @@ #include "../../feature/spindle_laser.h" #include "../../module/stepper.h" +inline cutter_power_t get_s_power() { + return cutter_power_t( + parser.intval('S', cutter.interpret_power(SPEED_POWER_STARTUP)) + ); +} + /** * Laser: * @@ -71,29 +77,52 @@ */ void GcodeSuite::M3_M4(const bool is_M4) { - #if ENABLED(SPINDLE_FEATURE) - planner.synchronize(); // Wait for movement to complete before changing power + #if ENABLED(LASER_POWER_INLINE) + if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { + // Laser power in inline mode + cutter.inline_direction(is_M4); // Should always be unused + + #if ENABLED(SPINDLE_LASER_PWM) + if (parser.seen('O')) + cutter.inline_ocr_power(parser.value_byte()); // The OCR is a value from 0 to 255 (uint8_t) + else + cutter.inline_power(get_s_power()); + #else + cutter.inline_enabled(true); + #endif + return; + } + // Non-inline, standard case + cutter.inline_disable(); // Prevent future blocks re-setting the power #endif + planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power + cutter.set_direction(is_M4); #if ENABLED(SPINDLE_LASER_PWM) if (parser.seenval('O')) cutter.set_ocr_power(parser.value_byte()); // The OCR is a value from 0 to 255 (uint8_t) else - cutter.set_power(parser.intval('S', 255)); + cutter.set_power(get_s_power()); #else cutter.set_enabled(true); #endif } /** - * M5 - Cutter OFF + * M5 - Cutter OFF (when moves are complete) */ void GcodeSuite::M5() { - #if ENABLED(SPINDLE_FEATURE) - planner.synchronize(); + #if ENABLED(LASER_POWER_INLINE) + if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { + cutter.inline_enabled(false); // Laser power in inline mode + return; + } + // Non-inline, standard case + cutter.inline_disable(); // Prevent future blocks re-setting the power #endif + planner.synchronize(); cutter.set_enabled(false); } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 1f9d710bb4..0937a86bd2 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -53,6 +53,10 @@ GcodeSuite gcode; #include "../feature/cancel_object.h" #endif +#if ENABLED(LASER_MOVE_POWER) + #include "../feature/spindle_laser.h" +#endif + #include "../MarlinCore.h" // for idle() millis_t GcodeSuite::previous_move_ms; @@ -172,6 +176,18 @@ void GcodeSuite::get_destination_from_command() { #if BOTH(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1) M165(); #endif + + #if ENABLED(LASER_MOVE_POWER) + // Set the laser power in the planner to configure this move + if (parser.seen('S')) + cutter.inline_power(parser.value_int()); + else { + #if ENABLED(LASER_MOVE_G0_OFF) + if (parser.codenum == 0) // G0 + cutter.inline_enabled(false); + #endif + } + #endif } /** diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 069d76fdad..df0825a512 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -69,7 +69,7 @@ void GcodeSuite::G0_G1( #endif #endif - get_destination_from_command(); // Process X Y Z E F parameters + get_destination_from_command(); // Get X Y Z E F (and set cutter power) #ifdef G0_FEEDRATE if (fast_move) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index b0fb299ab2..d6b18bdd95 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -283,7 +283,7 @@ void GcodeSuite::G2_G3(const bool clockwise) { relative_mode = true; #endif - get_destination_from_command(); + get_destination_from_command(); // Get X Y Z E F (and set cutter power) #if ENABLED(SF_ARC_FIX) relative_mode = relative_mode_backup; diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index a52ae1af29..cda744d81b 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -116,7 +116,23 @@ #define Z_STEPPER_ALIGN_AMP 1.0 #endif -#define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE) +// +// Spindle/Laser power display types +// Defined here so sanity checks can use them +// +#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) + #define HAS_CUTTER 1 + #define _CUTTER_DISP_PWM 1 + #define _CUTTER_DISP_PERCENT 2 + #define _CUTTER_DISP_RPM 3 + #define _CUTTER_DISP(V) _CAT(_CUTTER_DISP_, V) + #define CUTTER_DISPLAY_IS(V) (_CUTTER_DISP(CUTTER_POWER_DISPLAY) == _CUTTER_DISP(V)) +#endif + +// Add features that need hardware PWM here +#if ANY(FAST_PWM_FAN, SPINDLE_LASER_PWM) + #define NEEDS_HARDWARE_PWM 1 +#endif #if !defined(__AVR__) || !defined(USBCON) // Define constants and variables for buffering serial data. @@ -290,3 +306,17 @@ #define MAXIMUM_STEPPER_RATE 250000 #endif #endif + +// +// SD Card connection methods +// Defined here so pins and sanity checks can use them +// +#if ENABLED(SDSUPPORT) + #define _SDCARD_LCD 1 + #define _SDCARD_ONBOARD 2 + #define _SDCARD_CUSTOM_CABLE 3 + #define _SDCARD_ID(V) _CAT(_SDCARD_, V) + #define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V)) +#else + #define SD_CONNECTION_IS(...) 0 +#endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 20867b4fea..b38aaa1332 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -324,17 +324,36 @@ /** * Override the SD_DETECT_STATE set in Configuration_adv.h + * and enable sharing of onboard SD host drives (all platforms but AGCM4) */ #if ENABLED(SDSUPPORT) - #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) - #undef SD_DETECT_STATE - #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define SD_DETECT_STATE HIGH + + #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4) + // + // The external SD card is not used. Hardware SPI is used to access the card. + // When sharing the SD card with a PC we want the menu options to + // mount/unmount the card and refresh it. So we disable card detect. + // + #undef SD_DETECT_PIN + #define SHARED_SD_CARD + #endif + + #if DISABLED(SHARED_SD_CARD) + #define INIT_SDCARD_ON_BOOT 1 + #endif + + #if PIN_EXISTS(SD_DETECT) + #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #undef SD_DETECT_STATE + #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #define SD_DETECT_STATE HIGH + #endif + #endif + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE LOW #endif #endif - #ifndef SD_DETECT_STATE - #define SD_DETECT_STATE LOW - #endif + #endif /** @@ -2153,21 +2172,6 @@ #endif #endif -#if ENABLED(SDSUPPORT) - #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4) - // - // The external SD card is not used. Hardware SPI is used to access the card. - // When sharing the SD card with a PC we want the menu options to - // mount/unmount the card and refresh it. So we disable card detect. - // - #undef SD_DETECT_PIN - #define SHARED_SD_CARD - #endif - #if DISABLED(SHARED_SD_CARD) - #define INIT_SDCARD_ON_BOOT 1 - #endif -#endif - #if !NUM_SERIAL #undef BAUD_RATE_GCODE #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 2fd61d4be1..088ad098db 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1451,7 +1451,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. */ #if ENABLED(Z_PROBE_ALLEN_KEY) && (Z_HOME_DIR < 0) && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY" + #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY." #endif /** @@ -2654,9 +2654,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(BACKLASH_COMPENSATION) #ifndef BACKLASH_DISTANCE_MM - #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM" + #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM." #elif !defined(BACKLASH_CORRECTION) - #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION" + #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION." #elif IS_CORE constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], @@ -2736,6 +2736,45 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #if HAS_CUTTER + #ifndef CUTTER_POWER_DISPLAY + #error "CUTTER_POWER_DISPLAY is required with a spindle or laser. Please update your Configuration_adv.h." + #elif !CUTTER_DISPLAY_IS(PWM) && !CUTTER_DISPLAY_IS(PERCENT) && !CUTTER_DISPLAY_IS(RPM) + #error "CUTTER_POWER_DISPLAY must be PWM, PERCENT, or RPM. Please update your Configuration_adv.h." + #endif + + #if ENABLED(LASER_POWER_INLINE) + #if ENABLED(SPINDLE_CHANGE_DIR) + #error "SPINDLE_CHANGE_DIR and LASER_POWER_INLINE are incompatible." + #elif ENABLED(LASER_MOVE_G0_OFF) && DISABLED(LASER_MOVE_POWER) + #error "LASER_MOVE_G0_OFF requires LASER_MOVE_POWER. Please update your Configuration_adv.h." + #endif + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + #if DISABLED(SPINDLE_LASER_PWM) + #error "LASER_POWER_INLINE_TRAPEZOID requires SPINDLE_LASER_PWM to function." + #elif ENABLED(S_CURVE_ACCELERATION) + //#ifndef LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN + // #define LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN + // #warning "Combining LASER_POWER_INLINE_TRAPEZOID with S_CURVE_ACCELERATION may result in unintended behavior." + //#endif + #endif + #endif + #if ENABLED(LASER_POWER_INLINE_INVERT) + //#ifndef LASER_POWER_INLINE_INVERT_WARN + // #define LASER_POWER_INLINE_INVERT_WARN + // #warning "Enabling LASER_POWER_INLINE_INVERT means that `M5` won't kill the laser immediately; use `M5 I` instead." + //#endif + #endif + #else + #if SPINDLE_LASER_POWERUP_DELAY < 1 + #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0." + #elif SPINDLE_LASER_POWERDOWN_DELAY < 1 + #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0." + #elif ENABLED(LASER_MOVE_POWER) + #error "LASER_MOVE_POWER requires LASER_POWER_INLINE." + #elif ANY(LASER_POWER_INLINE_TRAPEZOID, LASER_POWER_INLINE_INVERT, LASER_MOVE_G0_OFF, LASER_MOVE_POWER) + #error "Enabled an inline laser feature without inline laser power being enabled." + #endif + #endif #define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN) #if BOTH(SPINDLE_FEATURE, LASER_FEATURE) #error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE." @@ -2748,13 +2787,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "SPINDLE_LASER_PWM_PIN is required for SPINDLE_LASER_PWM." #elif !PWM_PIN(SPINDLE_LASER_PWM_PIN) #error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin." - #elif SPINDLE_LASER_POWERUP_DELAY < 1 - #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0." - #elif SPINDLE_LASER_POWERDOWN_DELAY < 1 - #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0." #elif !defined(SPINDLE_LASER_PWM_INVERT) #error "SPINDLE_LASER_PWM_INVERT is required for (SPINDLE|LASER)_FEATURE." - #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX) + #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX) || !defined(SPEED_POWER_STARTUP) #error "SPINDLE_LASER_PWM equation constant(s) missing." #elif _PIN_CONFLICT(X_MIN) #error "SPINDLE_LASER_PWM pin conflicts with X_MIN_PIN." diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index be414ab303..b4bba3782c 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -570,8 +570,12 @@ void MarlinUI::draw_status_screen() { // Laser / Spindle #if DO_DRAW_CUTTER if (cutter.power && PAGE_CONTAINS(STATUS_CUTTER_TEXT_Y - INFO_FONT_ASCENT, STATUS_CUTTER_TEXT_Y - 1)) { - lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3rj(cutter.powerPercent(cutter.power))); - lcd_put_wchar('%'); + lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3rj(cutter.power)); + #if CUTTER_DISPLAY_IS(PERCENT) + lcd_put_wchar('%'); + #elif CUTTER_DISPLAY_IS(RPM) + lcd_put_wchar('K'); + #endif } #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 79a6f814b2..0aea571caa 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -90,6 +90,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Conf"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preheat Custom"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Cooldown"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequency"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser Control"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Off"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser On"); @@ -603,7 +604,7 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); - + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index fd42522839..d8e680ec3c 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -36,18 +36,29 @@ START_MENU(); BACK_ITEM(MSG_MAIN); - if (cutter.enabled()) { - #if ENABLED(SPINDLE_LASER_PWM) - EDIT_ITEM(CUTTER_MENU_TYPE, MSG_CUTTER(POWER), &cutter.power, SPEED_POWER_MIN, SPEED_POWER_MAX); - #endif + #if ENABLED(SPINDLE_LASER_PWM) + EDIT_ITEM_FAST(CUTTER_MENU_POWER_TYPE, MSG_CUTTER(POWER), &cutter.setPower, cutter.interpret_power(SPEED_POWER_MIN), cutter.interpret_power(SPEED_POWER_MAX), + []{ + if (cutter.isOn) { + cutter.power = cutter.setPower; + } + }); + #endif + + if (cutter.enabled() && cutter.isOn) ACTION_ITEM(MSG_CUTTER(OFF), cutter.disable); - } else { ACTION_ITEM(MSG_CUTTER(ON), cutter.enable_forward); #if ENABLED(SPINDLE_CHANGE_DIR) ACTION_ITEM(MSG_SPINDLE_REVERSE, cutter.enable_reverse); #endif } + + #if ENABLED(MARLIN_DEV_MODE) + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) + EDIT_ITEM_FAST(CUTTER_MENU_FREQUENCY_TYPE, MSG_CUTTER_FREQUENCY, &cutter.frequency, 2000, 50000,[]{ cutter.refresh_frequency();}); + #endif + #endif END_MENU(); } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e1a050a459..2de46373b2 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -815,11 +815,10 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e #if ENABLED(S_CURVE_ACCELERATION) // Jerk controlled speed requires to express speed versus time, NOT steps uint32_t acceleration_time = ((float)(cruise_rate - initial_rate) / accel) * (STEPPER_TIMER_RATE), - deceleration_time = ((float)(cruise_rate - final_rate) / accel) * (STEPPER_TIMER_RATE); - + deceleration_time = ((float)(cruise_rate - final_rate) / accel) * (STEPPER_TIMER_RATE), // And to offload calculations from the ISR, we also calculate the inverse of those times here - uint32_t acceleration_time_inverse = get_period_inverse(acceleration_time); - uint32_t deceleration_time_inverse = get_period_inverse(deceleration_time); + acceleration_time_inverse = get_period_inverse(acceleration_time), + deceleration_time_inverse = get_period_inverse(deceleration_time); #endif // Store new block parameters @@ -834,6 +833,47 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e block->cruise_rate = cruise_rate; #endif block->final_rate = final_rate; + + /** + * Laser trapezoid calculations + * + * Approximate the trapezoid with the laser, incrementing the power every `entry_per` while accelerating + * and decrementing it every `exit_power_per` while decelerating, thus ensuring power is related to feedrate. + * + * LASER_POWER_INLINE_TRAPEZOID_CONT doesn't need this as it continuously approximates + * + * Note this may behave unreliably when running with S_CURVE_ACCELERATION + */ + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (block->laser.power > 0) { // No need to care if power == 0 + const uint8_t entry_power = block->laser.power * entry_factor; // Power on block entry + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + // Speedup power + const uint8_t entry_power_diff = block->laser.power - entry_power; + if (entry_power_diff) { + block->laser.entry_per = accelerate_steps / entry_power_diff; + block->laser.power_entry = entry_power; + } + else { + block->laser.entry_per = 0; + block->laser.power_entry = block->laser.power; + } + // Slowdown power + const uint8_t exit_power = block->laser.power * exit_factor, // Power on block entry + exit_power_diff = block->laser.power - exit_power; + if (exit_power_diff) { + block->laser.exit_per = (block->step_event_count - block->decelerate_after) / exit_power_diff; + block->laser.power_exit = exit_power; + } + else { + block->laser.exit_per = 0; + block->laser.power_exit = block->laser.power; + } + #else + block->laser.power_entry = entry_power; + #endif + } + #endif } /* PLANNER SPEED DEFINITION @@ -1813,6 +1853,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Set direction bits block->direction_bits = dm; + // Update block laser power + #if ENABLED(LASER_POWER_INLINE) + block->laser.status = settings.laser.status; + block->laser.power = settings.laser.power; + #endif + // Number of steps for each axis // See http://www.corexy.com/theory.html #if CORE_IS_XY diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 24c02c01c5..a42c84c1fa 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -52,7 +52,7 @@ #endif #if HAS_CUTTER - #include "../feature/spindle_laser.h" + #include "../feature/spindle_laser_types.h" #endif // Feedrate for manual moves @@ -88,6 +88,23 @@ enum BlockFlag : char { BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) }; +#if ENABLED(LASER_POWER_INLINE) + + typedef struct { + uint8_t status, // See planner settings for meaning + power; // Ditto; When in trapezoid mode this is nominal power + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + uint8_t power_entry; // Entry power for the laser + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + uint8_t power_exit; // Exit power for the laser + uint32_t entry_per, // Steps per power increment (to avoid floats in stepper calcs) + exit_per; // Steps per power decrement + #endif + #endif + } block_laser_t; + +#endif + /** * struct block_t * @@ -174,12 +191,36 @@ typedef struct block_t { uint32_t sdpos; #endif + #if ENABLED(LASER_POWER_INLINE) + block_laser_t laser; + #endif + } block_t; #define HAS_POSITION_FLOAT ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX, LCD_SHOW_E_TOTAL) #define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1)) +#if ENABLED(LASER_POWER_INLINE) + typedef struct { + /** + * Laser status bitmask; most bits are unused; + * 0: Planner buffer enable + * 1: Laser enable + * 2: Reserved for direction + */ + uint8_t status; + /** + * Laser power: 0 or 255 in case of PWM-less laser, + * or the OCR value; + * + * Using OCR instead of raw power, + * as it avoids floating points during move loop + */ + uint8_t power; + } settings_laser_t; +#endif + typedef struct { uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE min_segment_time_us; // (µs) M205 B @@ -190,6 +231,9 @@ typedef struct { travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate + #if ENABLED(LASER_POWER_INLINE) + settings_laser_t laser; + #endif } planner_settings_t; #if DISABLED(SKEW_CORRECTION) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ed48b83d5a..f77a596b08 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -133,6 +133,10 @@ Stepper stepper; // Singleton #include "../feature/powerloss.h" #endif +#if HAS_CUTTER + #include "../feature/spindle_laser.h" +#endif + // public: #if HAS_EXTRA_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -236,6 +240,20 @@ xyz_long_t Stepper::endstops_trigsteps; xyze_long_t Stepper::count_position{0}; xyze_int8_t Stepper::count_direction{0}; +#if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + Stepper::stepper_laser_t Stepper::laser = { + .trap_en = false, + .cur_power = 0, + .cruise_set = false, + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + .last_step_count = 0, + .acc_step_count = 0 + #else + .till_update = 0 + #endif + }; +#endif + #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ if (A##_HOME_DIR < 0) { \ @@ -1674,10 +1692,9 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(S_CURVE_ACCELERATION) // Get the next speed to use (Jerk limited!) - uint32_t acc_step_rate = - acceleration_time < current_block->acceleration_time - ? _eval_bezier_curve(acceleration_time) - : current_block->cruise_rate; + uint32_t acc_step_rate = acceleration_time < current_block->acceleration_time + ? _eval_bezier_curve(acceleration_time) + : current_block->cruise_rate; #else acc_step_rate = STEP_MULTIPLY(acceleration_time, current_block->acceleration_rate) + current_block->initial_rate; NOMORE(acc_step_rate, current_block->nominal_rate); @@ -1690,9 +1707,40 @@ uint32_t Stepper::block_phase_isr() { acceleration_time += interval; #if ENABLED(LIN_ADVANCE) - // Fire ISR if final adv_rate is reached - if (LA_steps && (!LA_use_advance_lead || LA_isr_rate != current_block->advance_speed)) - initiateLA(); + if (LA_use_advance_lead) { + // Fire ISR if final adv_rate is reached + if (LA_steps && LA_isr_rate != current_block->advance_speed) nextAdvanceISR = 0; + } + else if (LA_steps) nextAdvanceISR = 0; + #endif + + // Update laser - Accelerating + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (laser.trap_en) { + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + if (current_block->laser.entry_per) { + laser.acc_step_count -= step_events_completed - laser.last_step_count; + laser.last_step_count = step_events_completed; + + // Should be faster than a divide, since this should trip just once + if (laser.acc_step_count < 0) { + while (laser.acc_step_count < 0) { + laser.acc_step_count += current_block->laser.entry_per; + if (laser.cur_power < current_block->laser.power) laser.cur_power++; + } + cutter.set_ocr_power(laser.cur_power); + } + } + #else + if (laser.till_update) + laser.till_update--; + else { + laser.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; + laser.cur_power = (current_block->laser.power * acc_step_rate) / current_block->nominal_rate; + cutter.set_ocr_power(laser.cur_power); // Cycle efficiency is irrelevant it the last line was many cycles + } + #endif + } #endif } // Are we in Deceleration phase ? @@ -1740,10 +1788,39 @@ uint32_t Stepper::block_phase_isr() { LA_isr_rate = current_block->advance_speed; } } - else if (LA_steps) initiateLA(); + else if (LA_steps) nextAdvanceISR = 0; + #endif // LIN_ADVANCE + + // Update laser - Decelerating + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (laser.trap_en) { + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + if (current_block->laser.exit_per) { + laser.acc_step_count -= step_events_completed - laser.last_step_count; + laser.last_step_count = step_events_completed; + + // Should be faster than a divide, since this should trip just once + if (laser.acc_step_count < 0) { + while (laser.acc_step_count < 0) { + laser.acc_step_count += current_block->laser.exit_per; + if (laser.cur_power > current_block->laser.power_exit) laser.cur_power--; + } + cutter.set_ocr_power(laser.cur_power); + } + } + #else + if (laser.till_update) + laser.till_update--; + else { + laser.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; + laser.cur_power = (current_block->laser.power * step_rate) / current_block->nominal_rate; + cutter.set_ocr_power(laser.cur_power); // Cycle efficiency isn't relevant when the last line was many cycles + } + #endif + } #endif } - // We must be in cruise phase otherwise + // Must be in cruise phase otherwise else { #if ENABLED(LIN_ADVANCE) @@ -1759,6 +1836,22 @@ uint32_t Stepper::block_phase_isr() { // The timer interval is just the nominal value for the nominal speed interval = ticks_nominal; + + // Update laser - Cruising + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (laser.trap_en) { + if (!laser.cruise_set) { + laser.cur_power = current_block->laser.power; + cutter.set_ocr_power(laser.cur_power); + laser.cruise_set = true; + } + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + laser.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; + #else + laser.last_step_count = step_events_completed; + #endif + } + #endif } } } @@ -1805,11 +1898,11 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == DeltaB, the movement is only in the 1st axis (X) */ #if EITHER(COREXY, COREXZ) - #define X_CMP == + #define X_CMP(A,B) ((A)==(B)) #else - #define X_CMP != + #define X_CMP(A,B) ((A)!=(B)) #endif - #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) X_CMP D_(2)) ) + #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && X_CMP(D_(1),D_(2))) ) #else #define X_MOVE_TEST !!current_block->steps.a #endif @@ -1823,11 +1916,11 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z) */ #if EITHER(COREYX, COREYZ) - #define Y_CMP == + #define Y_CMP(A,B) ((A)==(B)) #else - #define Y_CMP != + #define Y_CMP(A,B) ((A)!=(B)) #endif - #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Y_CMP D_(2)) ) + #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && Y_CMP(D_(1),D_(2))) ) #else #define Y_MOVE_TEST !!current_block->steps.b #endif @@ -1841,11 +1934,11 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z) */ #if EITHER(COREZX, COREZY) - #define Z_CMP == + #define Z_CMP(A,B) ((A)==(B)) #else - #define Z_CMP != + #define Z_CMP(A,B) ((A)!=(B)) #endif - #define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Z_CMP D_(2)) ) + #define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && Z_CMP(D_(1),D_(2))) ) #else #define Z_MOVE_TEST !!current_block->steps.c #endif @@ -1938,6 +2031,39 @@ uint32_t Stepper::block_phase_isr() { set_directions(); } + #if ENABLED(LASER_POWER_INLINE) + const uint8_t stat = current_block->laser.status; + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + laser.trap_en = (stat & 0x03) == 0x03; + laser.cur_power = current_block->laser.power_entry; // RESET STATE + laser.cruise_set = false; + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + laser.last_step_count = 0; + laser.acc_step_count = current_block->laser.entry_per / 2; + #else + laser.till_update = 0; + #endif + // Always have PWM in this case + if (TEST(stat, 0)) { // Planner controls the laser + if (TEST(stat, 1)) // Laser is on + cutter.set_ocr_power(laser.cur_power); + else + cutter.set_power(0); + } + #else + if (TEST(stat, 0)) { // Planner controls the laser + #if ENABLED(SPINDLE_LASER_PWM) + if (TEST(stat, 1)) // Laser is on + cutter.set_ocr_power(current_block->laser.power); + else + cutter.set_power(0); + #else + cutter.set_enabled(TEST(stat, 1)); + #endif + } + #endif + #endif // LASER_POWER_INLINE + // At this point, we must ensure the movement about to execute isn't // trying to force the head against a limit switch. If using interrupt- // driven change detection, and already against a limit then no call to @@ -1957,21 +2083,35 @@ uint32_t Stepper::block_phase_isr() { // Mark the time_nominal as not calculated yet ticks_nominal = -1; - #if DISABLED(S_CURVE_ACCELERATION) - // Set as deceleration point the initial rate of the block - acc_step_rate = current_block->initial_rate; - #endif - #if ENABLED(S_CURVE_ACCELERATION) // Initialize the Bézier speed curve _calc_bezier_curve_coeffs(current_block->initial_rate, current_block->cruise_rate, current_block->acceleration_time_inverse); // We haven't started the 2nd half of the trapezoid bezier_2nd_half = false; + #else + // Set as deceleration point the initial rate of the block + acc_step_rate = current_block->initial_rate; #endif // Calculate the initial timer interval interval = calc_timer_interval(current_block->initial_rate, &steps_per_isr); } + #if ENABLED(LASER_POWER_INLINE_CONTINUOUS) + else { // No new block found; so apply inline laser parameters + // This should mean ending file with 'M5 I' will stop the laser; thus the inline flag isn't needed + const uint8_t stat = planner.settings.laser.status; + if (TEST(stat, 0)) { // Planner controls the laser + #if ENABLED(SPINDLE_LASER_PWM) + if (TEST(stat, 1)) // Laser is on + cutter.set_ocr_power(planner.settings.laser.power); + else + cutter.set_power(0); + #else + cutter.set_enabled(TEST(stat, 1)); + #endif + } + } + #endif } // Return the interval to wait diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 46c6c1c16a..3876980ad0 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -339,23 +339,35 @@ class Stepper { static uint32_t acc_step_rate; // needed for deceleration start point #endif - // // Exact steps at which an endstop was triggered - // static xyz_long_t endstops_trigsteps; - // // Positions of stepper motors, in step units - // static xyze_long_t count_position; - // - // Current direction of stepper motors (+1 or -1) - // + // Current stepper motor directions (+1 or -1) static xyze_int8_t count_direction; - public: + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + typedef struct { + bool trap_en; // Trapezoid needed flag (i.e., laser on, planner in control) + uint8_t cur_power; // Current laser power + bool cruise_set; // Power set up for cruising? + + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + uint32_t last_step_count, // Step count from the last update + acc_step_count; // Bresenham counter for laser accel/decel + #else + uint16_t till_update; // Countdown to the next update + #endif + } stepper_laser_t; + + static stepper_laser_t laser; + + #endif + + public: // Initialize stepper hardware static void init(); From ed0799d65341f0efc30fadfc0246aba62e4e67a3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 4 Apr 2020 00:03:24 +0000 Subject: [PATCH 0100/1454] [cron] Bump distribution date (2020-04-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fce0c46b5c..74c38628c4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-03" + #define STRING_DISTRIBUTION_DATE "2020-04-04" #endif /** From bc01d8d023e1dc95d4cbff50fc22edde5a6ff3f4 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Fri, 3 Apr 2020 20:17:05 -0400 Subject: [PATCH 0101/1454] Toolchange touchup (#17395) Co-authored-by: Scott Lahteine --- Marlin/src/module/tool_change.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 2471581c8c..658671fb7e 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -821,7 +821,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool >= EXTRUDERS) return invalid_extruder_error(new_tool); - if (!no_move && !all_axes_homed()) { + if (!no_move && !homing_needed()) { no_move = true; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("No move (not homed)"); } @@ -1073,7 +1073,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #ifdef EVENT_GCODE_AFTER_TOOLCHANGE - if (!no_move) + if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); #endif From 65f6a373b0a77da23f0758d5d1520e404436cec0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Apr 2020 00:08:25 -0500 Subject: [PATCH 0102/1454] Refactor SD detect handler (#17380) Co-Authored-By: Eric Ptak --- Marlin/src/MarlinCore.cpp | 95 +++++++++++++++----------- Marlin/src/lcd/extui/ui_api.cpp | 23 +------ Marlin/src/lcd/ultralcd.cpp | 114 +++++++++++++++----------------- Marlin/src/lcd/ultralcd.h | 4 ++ Marlin/src/sd/cardreader.cpp | 36 ++++++++++ Marlin/src/sd/cardreader.h | 3 + 6 files changed, 156 insertions(+), 119 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5073c339cd..da3c6cbaa2 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -443,7 +443,6 @@ void startOrResumeJob() { /** * Minimal management of Marlin's core activities: - * - Check for Filament Runout * - Keep the command buffer full * - Check for maximum inactive time between commands * - Check for maximum inactive time between stepper commands @@ -454,13 +453,8 @@ void startOrResumeJob() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ - inline void manage_inactivity(const bool ignore_stepper_queue=false) { - #if HAS_FILAMENT_SENSOR - runout.run(); - #endif - if (queue.length < BUFSIZE) queue.get_available_commands(); const millis_t ms = millis(); @@ -644,9 +638,53 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } /** - * Standard idle routine keeps the machine alive + * Standard idle routine keeps the machine alive: + * - Core Marlin activities + * - Manage heaters (and Watchdog) + * - Max7219 heartbeat, animation, etc. + * + * Only after setup() is complete: + * - Handle filament runout sensors + * - Run HAL idle tasks + * - Handle Power-Loss Recovery + * - Run StallGuard endstop checks + * - Handle SD Card insert / remove + * - Handle USB Flash Drive insert / remove + * - Announce Host Keepalive state (if any) + * - Update the Print Job Timer state + * - Update the Beeper queue + * - Read Buttons and Update the LCD + * - Run i2c Position Encoders + * - Auto-report Temperatures / SD Status + * - Update the Prusa MMU2 + * - Handle Joystick jogging */ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { + + // Core Marlin activities + manage_inactivity(TERN_(ADVANCED_PAUSE_FEATURE, no_stepper_sleep)); + + // Manage Heaters (and Watchdog) + thermalManager.manage_heater(); + + // Max7219 heartbeat, animation, etc + #if ENABLED(MAX7219_DEBUG) + max7219.idle_tasks(); + #endif + + // Return if setup() isn't completed + if (marlin_state == MF_INITIALIZING) return; + + // Handle filament runout sensors + #if HAS_FILAMENT_SENSOR + runout.run(); + #endif + + // Run HAL idle tasks + #ifdef HAL_IDLETASK + HAL_idletask(); + #endif + // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) recovery.outage(); @@ -660,29 +698,21 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { if (endstops.tmc_spi_homing_check()) break; #endif - // Max7219 heartbeat, animation, etc. - #if ENABLED(MAX7219_DEBUG) - max7219.idle_tasks(); + // Handle SD Card insert / remove + #if ENABLED(SDSUPPORT) + card.manage_media(); #endif - // Read Buttons and Update the LCD - ui.update(); + // Handle USB Flash Drive insert / remove + #if ENABLED(USB_FLASH_DRIVE_SUPPORT) + Sd2Card::idle(); + #endif // Announce Host Keepalive state (if any) #if ENABLED(HOST_KEEPALIVE_FEATURE) gcode.host_keepalive(); #endif - // Core Marlin activities - manage_inactivity( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - no_stepper_sleep - #endif - ); - - // Manage heaters (and Watchdog) - thermalManager.manage_heater(); - // Update the Print Job Timer state #if ENABLED(PRINTCOUNTER) print_job_timer.tick(); @@ -693,6 +723,9 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { buzzer.tick(); #endif + // Read Buttons and Update the LCD + ui.update(); + // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) static millis_t i2cpem_next_update_ms; @@ -705,11 +738,6 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { } #endif - // Run HAL idle tasks - #ifdef HAL_IDLETASK - HAL_idletask(); - #endif - // Auto-report Temperatures / SD Status #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { @@ -722,11 +750,6 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { } #endif - // Handle USB Flash Drive insert / remove - #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - Sd2Card::idle(); - #endif - // Update the Prusa MMU2 #if ENABLED(PRUSA_MMU2) mmu2.mmu_loop(); @@ -983,8 +1006,8 @@ void setup() { SETUP_RUN(ui.show_bootscreen()); #endif - #if ENABLED(SDSUPPORT) && defined(SDCARD_CONNECTION) && !SD_CONNECTION_IS(LCD) - SETUP_RUN(card.mount()); // Mount onboard / custom SD card before settings.first_load + #if BOTH(SDSUPPORT, SDCARD_EEPROM_EMULATION) + SETUP_RUN(card.mount()); // Mount media with settings before first_load #endif SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) @@ -1151,10 +1174,6 @@ void setup() { queue.inject_P(PSTR(STARTUP_COMMANDS)); #endif - #if ENABLED(INIT_SDCARD_ON_BOOT) && !HAS_SPI_LCD - SETUP_RUN(card.beginautostart()); - #endif - #if ENABLED(HOST_PROMPT_SUPPORT) SETUP_RUN(host_action_prompt_end()); #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index a5b1460c90..d57adadfef 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1149,28 +1149,7 @@ void MarlinUI::init() { ExtUI::onStartup(); } -void MarlinUI::update() { - #if ENABLED(SDSUPPORT) - static bool last_sd_status; - const bool sd_status = IS_SD_INSERTED(); - if (sd_status != last_sd_status) { - last_sd_status = sd_status; - if (sd_status) { - card.mount(); - if (card.isMounted()) - ExtUI::onMediaInserted(); - else - ExtUI::onMediaError(); - } - else { - const bool ok = card.isMounted(); - card.release(); - if (ok) ExtUI::onMediaRemoved(); - } - } - #endif // SDSUPPORT - ExtUI::onIdle(); -} +void MarlinUI::update() { ExtUI::onIdle(); } void MarlinUI::kill_screen(PGM_P const error, PGM_P const component) { using namespace ExtUI; diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index ff0331eb20..10a717b6fe 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -121,10 +121,6 @@ MarlinUI ui; #endif #endif -#if ENABLED(INIT_SDCARD_ON_BOOT) - uint8_t lcd_sd_status; -#endif - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS bool MarlinUI::defer_return_to_status; #endif @@ -342,13 +338,8 @@ void MarlinUI::init() { #endif // HAS_SHIFT_ENCODER - #if ENABLED(SDSUPPORT) - #if PIN_EXISTS(SD_DETECT) - SET_INPUT_PULLUP(SD_DETECT_PIN); - #endif - #if ENABLED(INIT_SDCARD_ON_BOOT) - lcd_sd_status = 2; // UNKNOWN - #endif + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + SET_INPUT_PULLUP(SD_DETECT_PIN); #endif #if HAS_ENCODER_ACTION && HAS_SLOW_BUTTONS @@ -744,11 +735,11 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { */ LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; +millis_t next_lcd_update_ms; void MarlinUI::update() { static uint16_t max_display_update_time = 0; - static millis_t next_lcd_update_ms; millis_t ms = millis(); #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS @@ -824,53 +815,6 @@ void MarlinUI::update() { #endif // HAS_LCD_MENU - #if ENABLED(INIT_SDCARD_ON_BOOT) - // - // SPI SD Card detection (and first card init when the LCD is present) - // - const uint8_t sd_status = (uint8_t)IS_SD_INSERTED(); - if (sd_status != lcd_sd_status && detected()) { - - uint8_t old_sd_status = lcd_sd_status; // prevent re-entry to this block! - lcd_sd_status = sd_status; - - if (sd_status) { - safe_delay(500); // Some boards need a delay to get settled - card.mount(); - if (old_sd_status == 2) - card.beginautostart(); // Initial boot - else - set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); - } - #if PIN_EXISTS(SD_DETECT) - else { - card.release(); - if (old_sd_status != 2) { - set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); - #if HAS_LCD_MENU - return_to_status(); - #endif - } - } - - #if DISABLED(NO_LCD_REINIT) - init_lcd(); // May revive the LCD if static electricity killed it - #endif - - #endif - - refresh(); - - ms = millis(); - next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; // delay LCD update until after SD activity completes - - #ifdef LED_BACKLIGHT_TIMEOUT - leds.reset_timeout(ms); - #endif - } - - #endif // INIT_SDCARD_ON_BOOT - if (ELAPSED(ms, next_lcd_update_ms) #if HAS_GRAPHICAL_LCD || drawing_screen @@ -1595,3 +1539,55 @@ void MarlinUI::update() { } #endif // !HAS_DISPLAY + +#if ENABLED(SDSUPPORT) + + void MarlinUI::media_changed(const uint8_t old_status, const uint8_t status) { + if (old_status == status) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaError(); // Failed to mount/unmount + #endif + return; + } + + if (status) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); // ExtUI response + #endif + if (old_status < 2) + set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); + } + else { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); // ExtUI response + #endif + if (old_status < 2) { + #if PIN_EXISTS(SD_DETECT) + set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); + #if HAS_LCD_MENU + return_to_status(); + #endif + #endif + } + } + + #if PIN_EXISTS(SD_DETECT) && DISABLED(NO_LCD_REINIT) + init_lcd(); // Revive a noisy shared SPI LCD + #endif + + refresh(); + + #if HAS_SPI_LCD || defined(LED_BACKLIGHT_TIMEOUT) + const millis_t ms = millis(); + #endif + + #if HAS_SPI_LCD + next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; // Delay LCD update for SD activity + #endif + + #ifdef LED_BACKLIGHT_TIMEOUT + leds.reset_timeout(ms); + #endif + } + +#endif // SDSUPPORT diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 2737a1a648..0be82ff1f6 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -274,6 +274,10 @@ public: // LCD implementations static void clear_lcd(); + #if ENABLED(SDSUPPORT) + static void media_changed(const uint8_t old_stat, const uint8_t stat); + #endif + #if HAS_SPI_LCD static bool detected(); static void init_lcd(); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 80e94b88b5..63607f7bbd 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -378,6 +378,42 @@ void CardReader::mount() { ui.refresh(); } +/** + * Handle SD card events + */ +#if MB(FYSETC_CHEETAH) + #include "../module/stepper.h" +#endif + +void CardReader::manage_media() { + static uint8_t prev_stat = TERN(INIT_SDCARD_ON_BOOT, 2, 0); + uint8_t stat = uint8_t(IS_SD_INSERTED()); + if (stat != prev_stat && ui.detected()) { + + uint8_t old_stat = prev_stat; + prev_stat = stat; // Change now to prevent re-entry + + if (stat) { // Media Inserted + safe_delay(500); // Some boards need a delay to get settled + mount(); // Try to mount the media + #if MB(FYSETC_CHEETAH) + reset_stepper_drivers(); // Workaround for Cheetah bug + #endif + if (!isMounted()) stat = 0; // Not mounted? + } + else { + #if PIN_EXISTS(SD_DETECT) + release(); // Card is released + #endif + } + + ui.media_changed(old_stat, stat); // Update the UI + + if (stat && old_stat == 2) // First mount? + beginautostart(); // Look for autostart files soon + } +} + void CardReader::release() { endFilePrint(); flag.mounted = false; diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 955a8b69b3..1fee807495 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -73,6 +73,9 @@ public: static inline bool isMounted() { return flag.mounted; } static void ls(); + // Handle media insert/remove + static void manage_media(); + // SD Card Logging static void openLogFile(char * const path); static void write_command(char * const buf); From 723d4d6f610e922dbdc56e7f4f69e4a15ebb0fc8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Apr 2020 02:18:01 -0500 Subject: [PATCH 0103/1454] Fix Archim 2 build for PIO --- Marlin/Makefile | 2 +- Marlin/src/pins/pins.h | 2 +- platformio.ini | 19 +++++++++++++++++++ 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index 0a9b3a45d7..33a787fb64 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -686,7 +686,7 @@ ifeq ($(HARDWARE_VARIANT), Teensy) else ifeq ($(HARDWARE_VARIANT), archim) CDEFS += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSB_VID=0x27b1 -DUSB_PID=0x0001 -DUSBCON '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT="Archim"' - LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp + LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp LIB_SRC += cortex_handlers.c iar_calls_sam3.c syscalls_sam3.c dtostrf.c itoa.c ifeq ($(U8GLIB), 1) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 5de75a1f0e..a1095e23e2 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -454,7 +454,7 @@ #elif MB(ARCHIM1) #include "sam/pins_ARCHIM1.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(ARCHIM2) - #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE env:DUE_debug + #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug #elif MB(ALLIGATOR) #include "sam/pins_ALLIGATOR_R2.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(ADSK) diff --git a/platformio.ini b/platformio.ini index 4e801713a0..bf3dea01bc 100644 --- a/platformio.ini +++ b/platformio.ini @@ -206,6 +206,25 @@ build_flags = ${common.build_flags} -funwind-tables -mpoke-function-name +# +# Archim SAM +# +[env:DUE_archim] +platform = atmelsam +board = due +src_filter = ${common.default_src_filter} + +build_flags = ${common.build_flags} + -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON + +[env:DUE_archim_debug] +# Used when WATCHDOG_RESET_MANUAL is enabled +platform = atmelsam +board = due +src_filter = ${common.default_src_filter} + +build_flags = ${common.build_flags} + -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON + -funwind-tables -mpoke-function-name + # # NXP LPC176x ARM Cortex-M3 # From 0e06aaa2bc5c58e018fcdd466ae8836ac0c38e13 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2020 19:49:45 -0500 Subject: [PATCH 0104/1454] Add millis helper macros --- Marlin/src/MarlinCore.cpp | 4 ++-- Marlin/src/core/millis_t.h | 4 ++++ Marlin/src/feature/controllerfan.cpp | 2 +- Marlin/src/feature/pause.cpp | 4 ++-- Marlin/src/feature/power.cpp | 2 +- Marlin/src/gcode/calibrate/G76_M871.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/libs/stopwatch.cpp | 3 +-- Marlin/src/module/temperature.cpp | 24 ++++++++++++------------ Marlin/src/module/temperature.h | 2 +- 10 files changed, 26 insertions(+), 23 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index da3c6cbaa2..d05c9c6014 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -227,7 +227,7 @@ bool wait_for_heatup = true; // Inactivity shutdown millis_t max_inactive_time, // = 0 - stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL; + stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME); #if PIN_EXISTS(CHDK) extern millis_t chdk_timeout; @@ -543,7 +543,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { #if ENABLED(EXTRUDER_RUNOUT_PREVENT) if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP - && ELAPSED(ms, gcode.previous_move_ms + (EXTRUDER_RUNOUT_SECONDS) * 1000UL) + && ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS)) && !planner.has_blocks_queued() ) { #if ENABLED(SWITCHING_EXTRUDER) diff --git a/Marlin/src/core/millis_t.h b/Marlin/src/core/millis_t.h index 39ea17b9f0..bf0b0bb308 100644 --- a/Marlin/src/core/millis_t.h +++ b/Marlin/src/core/millis_t.h @@ -25,5 +25,9 @@ typedef uint32_t millis_t; +#define SEC_TO_MS(N) millis_t((N)*1000UL) +#define MIN_TO_MS(N) SEC_TO_MS((N)*60UL) +#define MS_TO_SEC(N) millis_t((N)/1000UL) + #define PENDING(NOW,SOON) ((int32_t)(NOW-(SOON))<0) #define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON)) diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 0746700407..debfdea1f9 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -91,7 +91,7 @@ void ControllerFan::update() { // - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds. // - If System is on idle and idle fan speed settings is activated. set_fan_speed( - settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + settings.duration * 1000UL) + settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + SEC_TO_MS(settings.duration)) ? settings.active_speed : settings.idle_speed ); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 23fa2fee01..259b130822 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -485,7 +485,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep #endif // Start the heater idle timers - const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; + const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); @@ -549,7 +549,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep show_continue_prompt(is_reload); // Start the heater idle timers - const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; + const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 1fa751811e..510747d208 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -98,7 +98,7 @@ void Power::check() { nextPowerCheck = ms + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + (POWER_TIMEOUT) * 1000UL)) + else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT))) power_off(); } } diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index c878f83a17..4bc27b82f5 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -182,7 +182,7 @@ void GcodeSuite::G76() { do_blocking_move_to(parkpos); // Wait for heatbed to reach target temp and probe to cool below target temp - if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + 900UL * 1000UL)) { + if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) { SERIAL_ECHOLNPGM("!Bed heating timeout."); break; } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0937a86bd2..57abc37b0d 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -988,7 +988,7 @@ void GcodeSuite::process_subcommands_now(char * gcode) { break; } } - next_busy_signal_ms = ms + host_keepalive_interval * 1000UL; + next_busy_signal_ms = ms + SEC_TO_MS(host_keepalive_interval); } #endif // HOST_KEEPALIVE_FEATURE diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index 6b01158cb9..c75eb2da09 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -106,8 +106,7 @@ void Stopwatch::reset() { } millis_t Stopwatch::duration() { - return ((isRunning() ? millis() : stopTimestamp) - - startTimestamp) / 1000UL + accumulator; + return accumulator + MS_TO_SEC((isRunning() ? millis() : stopTimestamp) - startTimestamp); } #if ENABLED(DEBUG_STOPWATCH) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index af2f1a10e8..f9f311635e 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -399,7 +399,7 @@ volatile bool Temperature::raw_temps_ready = false; const uint16_t watch_temp_period = GTV(WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); const uint8_t watch_temp_increase = GTV(WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); const float watch_temp_target = target - float(watch_temp_increase + GTV(TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1); - millis_t temp_change_ms = next_temp_ms + watch_temp_period * 1000UL; + millis_t temp_change_ms = next_temp_ms + SEC_TO_MS(watch_temp_period); float next_watch_temp = 0.0; bool heated = false; #endif @@ -546,7 +546,7 @@ volatile bool Temperature::raw_temps_ready = false; if (!heated) { // If not yet reached target... if (current_temp > next_watch_temp) { // Over the watch temp? next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for - temp_change_ms = ms + watch_temp_period * 1000UL; // - move the expiration timer up + temp_change_ms = ms + SEC_TO_MS(watch_temp_period); // - move the expiration timer up if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired @@ -2051,7 +2051,7 @@ void Temperature::init() { #endif if (current >= tr_target_temperature[heater_index] - hysteresis_degc) { - sm.timer = millis() + period_seconds * 1000UL; + sm.timer = millis() + SEC_TO_MS(period_seconds); break; } else if (PENDING(millis(), sm.timer)) break; @@ -3124,7 +3124,7 @@ void Temperature::tick() { millis_t residency_start_ms = 0; bool first_loop = true; // Loop until the temperature has stabilized - #define TEMP_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_RESIDENCY_TIME) * 1000UL)) + #define TEMP_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_RESIDENCY_TIME))) #else // Loop until the temperature is very close target #define TEMP_CONDITIONS (wants_to_cool ? isCoolingHotend(target_extruder) : isHeatingHotend(target_extruder)) @@ -3160,7 +3160,7 @@ void Temperature::tick() { #if TEMP_RESIDENCY_TIME > 0 SERIAL_ECHOPGM(" W:"); if (residency_start_ms) - SERIAL_ECHO(long((((TEMP_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + SERIAL_ECHO(long((SEC_TO_MS(TEMP_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); else SERIAL_CHAR('?'); #endif @@ -3185,7 +3185,7 @@ void Temperature::tick() { // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time. if (temp_diff < TEMP_WINDOW) { residency_start_ms = now; - if (first_loop) residency_start_ms += (TEMP_RESIDENCY_TIME) * 1000UL; + if (first_loop) residency_start_ms += SEC_TO_MS(TEMP_RESIDENCY_TIME); } } else if (temp_diff > TEMP_HYSTERESIS) { @@ -3247,7 +3247,7 @@ void Temperature::tick() { millis_t residency_start_ms = 0; bool first_loop = true; // Loop until the temperature has stabilized - #define TEMP_BED_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_BED_RESIDENCY_TIME) * 1000UL)) + #define TEMP_BED_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_BED_RESIDENCY_TIME))) #else // Loop until the temperature is very close target #define TEMP_BED_CONDITIONS (wants_to_cool ? isCoolingBed() : isHeatingBed()) @@ -3284,7 +3284,7 @@ void Temperature::tick() { #if TEMP_BED_RESIDENCY_TIME > 0 SERIAL_ECHOPGM(" W:"); if (residency_start_ms) - SERIAL_ECHO(long((((TEMP_BED_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + SERIAL_ECHO(long((SEC_TO_MS(TEMP_BED_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); else SERIAL_CHAR('?'); #endif @@ -3309,7 +3309,7 @@ void Temperature::tick() { // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time. if (temp_diff < TEMP_BED_WINDOW) { residency_start_ms = now; - if (first_loop) residency_start_ms += (TEMP_BED_RESIDENCY_TIME) * 1000UL; + if (first_loop) residency_start_ms += SEC_TO_MS(TEMP_BED_RESIDENCY_TIME); } } else if (temp_diff > TEMP_BED_HYSTERESIS) { @@ -3373,7 +3373,7 @@ void Temperature::tick() { millis_t residency_start_ms = 0; bool first_loop = true; // Loop until the temperature has stabilized - #define TEMP_CHAMBER_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL)) + #define TEMP_CHAMBER_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_CHAMBER_RESIDENCY_TIME))) #else // Loop until the temperature is very close target #define TEMP_CHAMBER_CONDITIONS (wants_to_cool ? isCoolingChamber() : isHeatingChamber()) @@ -3405,7 +3405,7 @@ void Temperature::tick() { #if TEMP_CHAMBER_RESIDENCY_TIME > 0 SERIAL_ECHOPGM(" W:"); if (residency_start_ms) - SERIAL_ECHO(long((((TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + SERIAL_ECHO(long((SEC_TO_MS(TEMP_CHAMBER_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); else SERIAL_CHAR('?'); #endif @@ -3425,7 +3425,7 @@ void Temperature::tick() { // Start the TEMP_CHAMBER_RESIDENCY_TIME timer when we reach target temp for the first time. if (temp_diff < TEMP_CHAMBER_WINDOW) { residency_start_ms = now; - if (first_loop) residency_start_ms += (TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL; + if (first_loop) residency_start_ms += SEC_TO_MS(TEMP_CHAMBER_RESIDENCY_TIME); } } else if (temp_diff > TEMP_CHAMBER_HYSTERESIS) { diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 24e0054496..cba1642afd 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -241,7 +241,7 @@ struct HeaterWatch { const int16_t newtarget = curr + INCREASE; if (newtarget < tgt - HYSTERESIS - 1) { target = newtarget; - next_ms = millis() + PERIOD * 1000UL; + next_ms = millis() + SEC_TO_MS(PERIOD); return; } } From da0f63cd1c854cf9018720ebaa3518e751f7a37f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 5 Apr 2020 00:02:50 +0000 Subject: [PATCH 0105/1454] [cron] Bump distribution date (2020-04-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 74c38628c4..d24a9dbefa 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-04" + #define STRING_DISTRIBUTION_DATE "2020-04-05" #endif /** From 8dd9afe4f9837df50d905b25197847928cefa087 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 12:54:46 -0500 Subject: [PATCH 0106/1454] Better push in 'mfpub' --- buildroot/share/git/mfpub | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 8ec28ad489..53911d6d4e 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -67,11 +67,11 @@ if [[ $BRANCH == $TARG ]]; then # Allow working directly with the main fork echo echo -n "Pushing to origin/$TARG... " - git push -f origin + git push origin HEAD:$TARG echo echo -n "Pushing to upstream/$TARG... " - git push -f upstream + git push upstream HEAD:$TARG else From 86a3efda6f1363ada61f3a6c1f469af18bc8576e Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sun, 5 Apr 2020 03:51:05 +0200 Subject: [PATCH 0107/1454] Update Italian language (#17407) --- Marlin/src/lcd/language/language_it.h | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 8d8112d523..c7f0585df5 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -88,6 +88,7 @@ namespace Language_it { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preris.") PREHEAT_2_LABEL _UxGT(" conf"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Raffredda"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenza"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Controllo laser"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Off"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser On"); @@ -349,7 +350,8 @@ namespace Language_it { PROGMEM Language_Str MSG_USERWAIT = _UxGT("Premi tasto.."); PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Stampa sospesa"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Stampa..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Stampa annullata"); + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Stampa Annullata"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Stampa Eseguita"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Nessun Movimento"); PROGMEM Language_Str MSG_KILLED = _UxGT("UCCISO. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("ARRESTATO. "); @@ -368,6 +370,7 @@ namespace Language_it { PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Risalita Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Velocità innesco"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Velocità retrazione"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Ugello Parcheggiato"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Standby ugello"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambia filamento *"); @@ -581,7 +584,7 @@ namespace Language_it { PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Drivers TMC"); PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver in uso"); PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Soglia modo ibrido"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Azzer. sensorless"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Azzer. senza sens."); PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo stepping"); PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop abil."); @@ -593,5 +596,11 @@ namespace Language_it { PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Livello asse X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibra"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout riscaldatore"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Riscalda"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Riscaldando..."); } From 07b3f38269c605fb79eab53516ddaef33155fb05 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Apr 2020 23:51:11 -0500 Subject: [PATCH 0108/1454] First SD status change is silent --- Marlin/src/lcd/ultralcd.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 10a717b6fe..08597451a0 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1551,17 +1551,18 @@ void MarlinUI::update() { } if (status) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaInserted(); // ExtUI response - #endif - if (old_status < 2) + if (old_status < 2) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); // ExtUI response + #endif set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); + } } else { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaRemoved(); // ExtUI response - #endif if (old_status < 2) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); // ExtUI response + #endif #if PIN_EXISTS(SD_DETECT) set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); #if HAS_LCD_MENU From fad9235cd80f2acdf1c0658d9633857fad94edea Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 5 Apr 2020 18:24:50 -0500 Subject: [PATCH 0109/1454] Move MSG_x_LINE to multi_language.h --- Marlin/src/core/multi_language.h | 4 ++++ Marlin/src/lcd/language/language_en.h | 4 ---- Marlin/src/lcd/language/language_pl.h | 4 ---- Marlin/src/lcd/language/language_tr.h | 4 ---- Marlin/src/lcd/language/language_zh_TW.h | 4 ---- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 6 ++++-- 6 files changed, 8 insertions(+), 18 deletions(-) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 98020b1e8d..ce8ce94fdc 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -77,3 +77,7 @@ typedef const char Language_Str[]; #define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG) #define MSG_CONCAT(A,B) pgm_p_pair_t(GET_TEXT(A),GET_TEXT(B)) + +#define MSG_1_LINE(A) A "\0" "\0" +#define MSG_2_LINE(A,B) A "\0" B "\0" +#define MSG_3_LINE(A,B,C) A "\0" B "\0" C diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 0aea571caa..2037d0c928 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -557,10 +557,6 @@ namespace Language_en { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 113c58629f..9fefeb6ee0 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -523,10 +523,6 @@ namespace Language_pl { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 096fef254c..515f4d0037 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -549,10 +549,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Değişim ekranları 4 satırlı ekranda 3 satıra kadar gösterilir // ...veya 3 satırlı ekranda 2 satıra kadar diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 06b19440f2..053a90d586 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -546,10 +546,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 1d1ad60f24..c4226001e6 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -26,8 +26,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif /** * Trinamic Stallguard pins From c47feb1cfe95c10b7166ef12d94c7e5b1b615846 Mon Sep 17 00:00:00 2001 From: Brais Fortes Date: Mon, 6 Apr 2020 01:36:27 +0200 Subject: [PATCH 0110/1454] Update Galician language (#17418) --- Marlin/src/core/language.h | 2 +- Marlin/src/lcd/language/language_gl.h | 518 ++++++++++++++++++++++---- 2 files changed, 455 insertions(+), 65 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index f58ace7709..a166de59ca 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -185,7 +185,7 @@ #define STR_INVALID_POS_SLOT "Invalid slot. Total: " #define STR_SD_CANT_OPEN_SUBDIR "Cannot open subdir " -#define STR_SD_INIT_FAIL "SD init fail" +#define STR_SD_INIT_FAIL "No SD card" #define STR_SD_VOL_INIT_FAIL "volume.init failed" #define STR_SD_OPENROOT_FAIL "openRoot failed" #define STR_SD_CARD_OK "SD card ok" diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 6a8f166ff1..c40c0c1f7d 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -39,22 +39,39 @@ namespace Language_gl { PROGMEM Language_Str LANGUAGE = _UxGT("Galician"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" lista."); + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); + PROGMEM Language_Str MSG_YES = _UxGT("SI"); + PROGMEM Language_Str MSG_NO = _UxGT("NON"); + PROGMEM Language_Str MSG_BACK = _UxGT("Atrás"); + PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); + PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD/USB lanzado"); + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/USB"); + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); + PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); + PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); + PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); + PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); + PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Axustes avanzados"); + PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuración"); PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autoarranque"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); + PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); + PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progreso"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ir a orixe"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Ir orixe X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Ir orixe Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Ir orixe Z"); + PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autoaliñar Z"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Ir orixes XYZ"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Prema pulsador"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Seguinte punto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivelado feito"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Offsets na orixe"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets fixados"); + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Fin Nivelación!"); + PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Compensación Altura"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Axustar Desfases"); + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfases aplicados"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Fixar orixe"); PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Prequentar ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Prequentar ") PREHEAT_1_LABEL " ~"; @@ -70,19 +87,151 @@ namespace Language_gl { PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preque. ") PREHEAT_2_LABEL _UxGT(" Todo"); PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preque. ") PREHEAT_2_LABEL _UxGT(" Cama"); PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preque. ") PREHEAT_2_LABEL _UxGT(" conf"); + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preque. Personali."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Arrefriar"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Láser Apagado"); + PROGMEM Language_Str MSG_LASER_ON = _UxGT("Láser Aceso"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Fuso"); + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Fuso Apagado"); + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Fuso Aceso"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Fuso"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverter xiro"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Acender"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Apagar"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudir"); + PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extruír"); PROGMEM Language_Str MSG_RETRACT = _UxGT("Retraer"); PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixe"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelar cama"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar cama"); + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); + PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); + PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Cantos"); + PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Seguinte Canto"); + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); + PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); + PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Ed. Mallado Detida"); + PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Punto de Proba"); + PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); + PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); + PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); + PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comandos Personaliz."); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); + PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); + PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Ferramentas Compens"); + PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Estacionar"); + PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicación"); + PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Espello"); + PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2º Bico X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2º Bico Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2º Bico Z"); + PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Executando G29"); + PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); + PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Facer Malla Manual"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Colocar Calzo e Medir"); + PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Medir"); + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Quitar e Medir Cama"); + PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Mover ao Seguinte"); + PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); + PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp Cama"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp Cama"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp Bico"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp Bico"); + PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Malla"); + PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Malla Person."); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Axuste Fino da Malla"); + PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Fin Edición da Malla"); + PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Malla Person."); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Malla"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M1 = _UxGT("Crear Malla (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M2 = _UxGT("Crear Malla (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Malla Fría"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Axustar Altura Malla"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Altura"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Malla"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("Validar Malla (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("Validar Malla (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validar Malla perso."); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Quentando Cama"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Quentando Bico"); + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Traballo manual..."); + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Traballo Lonxit Fixa"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Fin Traballo"); + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Cancelado"); + PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Saíndo de G26"); + PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Continuar Malla"); + PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nivelación Malla"); + PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelación 3Puntos"); + PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivelación Grid"); + PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivelar Malla"); + PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterais"); + PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo de Mapa "); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Gardar Mapa"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Enviar ao Host"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Gardar en CSV"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Backup Externo"); + PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Info do UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidade de Recheo"); + PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Recheo Manual"); + PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Recheo Intelixente"); + PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Recheo da Malla"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar todo"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar cercanos"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Axustar Fino Todo"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Axustar Fino Cerc"); + PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacenamento Malla"); + PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Rañura Memoria"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Malla Cama"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Gardar Malla Cama"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Malla %i Cargada"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Malla %i Gardada"); + PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sen Gardar"); + PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Erro: Gardadado UBL"); + PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Erro: Recuperación UBL"); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); + PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Detido"); + PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Crear Malla Fría"); + PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Recheo Intelixente"); + PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validar Malla"); + PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Axustar Fino Todo"); + PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validar Malla"); + PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Axustar Fino Todo"); + PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Gardar Malla Cama"); + + PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Control LED"); + PROGMEM Language_Str MSG_LEDS = _UxGT("Luces"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Axustes Luz"); + PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Vermello"); + PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Laranxa"); + PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Amarelo"); + PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Verde"); + PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Azul"); + PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Índigo"); + PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); + PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Branco"); + PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luces personalizadas"); + PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensidade Vermello"); + PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensidade Verde"); + PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensidade Azul"); + PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensidade Branco"); + PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brillo"); + + PROGMEM Language_Str MSG_MOVING = _UxGT("Movendo..."); + PROGMEM Language_Str MSG_FREE_XY = _UxGT("Libre XY"); PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); @@ -91,17 +240,66 @@ namespace Language_gl { PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bico"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Bico ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Bico Estacionado"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Bico Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Cama"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Velocidade vent."); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Velocidade vent. ~"); + PROGMEM Language_Str MSG_CHAMBER = _UxGT("Cámara"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. Ventilador"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. Ventilador ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventilador Mem. ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Vent. Extra"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Vent. Extra ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidade Repouso"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidade Activa"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo Repouso"); PROGMEM Language_Str MSG_FLOW = _UxGT("Fluxo"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Fluxo ~"); + PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temperatura Auto."); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("Acender"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apagar"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Auto-Sint. PID"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Auto-Sint. PID *"); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Escolla"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Escolla *"); PROGMEM Language_Str MSG_ACC = _UxGT("Acel"); + PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); + PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidade"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("V-viaxe min"); + PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Aceleración"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrac."); + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-viaxe"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); @@ -114,102 +312,294 @@ namespace Language_gl { PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. fil. *"); + PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); + PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carga mm"); + PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avance K"); + PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Avance K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Constraste LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gardar en memo."); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar de memo."); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Cargar de firm."); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Volver a cargar"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Monitorizacion"); + PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gardar Configuración"); + PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar Configuración"); + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Rest. Defecto"); + PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Erro: CRC EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Erro: Índice EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Erro: Versión EEPROM"); + PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); + PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reiniciar Impresora"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Información"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); PROGMEM Language_Str MSG_TUNE = _UxGT("Axustar"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impres."); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Seguir impres."); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Deter impres."); + PROGMEM Language_Str MSG_START_PRINT = _UxGT("Comezar impresión"); + PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Seguinte"); + PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Comezar"); + PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Deter"); + PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimir"); + PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reiniciar"); + PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancelar"); + PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Listo"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Atrás"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceder"); + PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); + PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Retomar impresión"); + PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Deter impresión"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimindo Obxecto"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Obxecto"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Obxecto ="); + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impresión"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Tarxeta SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Sen tarxeta SD"); PROGMEM Language_Str MSG_DWELL = _UxGT("En repouso..."); PROGMEM Language_Str MSG_USERWAIT = _UxGT("A espera..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impre. cancelada"); + PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Prema para Retomar"); + PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimindo..."); + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impresión Cancelada"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Fin Impresión"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sen movemento."); - PROGMEM Language_Str MSG_KILLED = _UxGT("PROGRAMA MORTO"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("PROGRAMA PARADO"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraccion mm"); + PROGMEM Language_Str MSG_KILLED = _UxGT("MORTO."); + PROGMEM Language_Str MSG_STOPPED = _UxGT("DETIDO."); + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Cambio retra. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraccion V"); + PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraer V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Alzar Z mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Recup. retra. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Cambio recup. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Recuperacion V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Retraccion auto."); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar filamen."); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar filamen. *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciando SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda-Z sen cama"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Comprobar BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Iniciar BLTouch"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retracción"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lonxitude Retracción"); + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lonxitude de Purga"); + PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Ferramenta"); + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Velocidade prim."); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Vel. de Retracción"); + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar Filamento"); + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar Filamento *"); + PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar Filamento"); + PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Cargar Filamento *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Descargar Filamento"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Descargar Filamento *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar Todo"); + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); + PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); + PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda-Z fóra Cama"); + PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Factor de Desviación"); + PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Cmd: Auto-Test"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Cmd: Reiniciar"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Cmd: Recoller"); + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Cmd: Estender"); + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Cmd: Modo Software"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Cmd: Modo 5V"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Cmd: Modo OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Cmd: Modo Almacenar"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Axustar BLTouch a 5V"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Axustar BLTouch a OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Modo de Informe"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERIGO: Unha mala configuración pode producir daños! Proceder igualmente?"); + PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test de Desfase Z"); + PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Gardar"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Estender TouchMI"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Estender Sonda Z"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Recoller Sonda Z"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Orixe %s%s%s Primeiro"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desfases Sonda"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desfase Sonda X"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desfase Sonda Y"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Erro fin carro"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fallo quentando"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro temperatura"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Temp. excesiva"); - PROGMEM Language_Str MSG_HALTED = _UxGT("SISTEMA MORTO"); + PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); + PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Erro FinCarro"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fallo Quentando"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Fallo Quent. Cama"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Fallo Quent. Cámara"); + PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CÁMARA"); + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Erro:TEMP MÁX"); + PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Erro:TEMP MÍN"); + PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Erro:TEMP MÁX CAMA"); + PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Erro:TEMP MÍN CAMA"); + PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Erro:TEMP MÁX CÁMARA"); + PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Erro:TEMP MÍN CÁMARA"); + PROGMEM Language_Str MSG_ERR_Z_HOMING = _UxGT("Orixe XY Primeiro"); + PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESORA DETIDA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Debe reiniciar!"); + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only + PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // One character only + PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only PROGMEM Language_Str MSG_HEATING = _UxGT("Quentando..."); + PROGMEM Language_Str MSG_COOLING = _UxGT("Arrefriando..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Quentando cama..."); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Enfriando Cama..."); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Quentando Cámara..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Arrefriando Cámara..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); + PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); + PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ax. Altura Delta"); + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Axustar Sonda Z"); + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); + PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altura"); + PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radio"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Acerca de..."); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Informacion"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estadisticas"); + PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Información"); + PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelación 3puntos"); + PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelación Lineal"); + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Nivelación Bilineal"); + PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Nivelación UBL"); + PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nivelación en Malla"); + PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estatísticas"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Placa nai"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudios"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Reloxo Traballo: OFF"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Reloxo Traballo: ON"); + + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz da Caixa"); + PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo Luces"); + PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); + #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total traballos"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Total completos"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo impresion"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Traballo +longo"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total extruido"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total Impresións"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo Total Imp."); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Impresión máis longa"); + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruído"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Traballos"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completos"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("O +longo"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impresións"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Máis Longa"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fonte alime."); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potencia motor"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Garda DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Segue traballo"); + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp Mín"); + PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); + PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fonte Alimentación"); + PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); + PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESIÓN PAUSADA"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARGAR FILAMENTO"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARGAR FILAMENTO"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCIÓN DE RETOMAR:"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar máis"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Retomar traballo"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bico: "); + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor Filamento"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm Sensor Fil"); + PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); + PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Fallo ao Sondar"); + PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Moi Frío"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); + PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLLE FILAMENTO"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Actualizar FW MMU!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Precisa Atención."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Retomar impr."); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Retomando..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Cargar Filamento"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Cargar Todo"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Cargar até bico"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Expulsar Filamento"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Expulsar Filamento ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Descargar Filamento"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Cargando Fil. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Expulsando Fil. ..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Descargando Fil..."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Todo"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reiniciar MMU"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Reiniciando MMU..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Expulsar, premer"); + + PROGMEM Language_Str MSG_MIX = _UxGT("Mestura"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Compoñente ="); + PROGMEM Language_Str MSG_MIXER = _UxGT("Mesturadora"); + PROGMEM Language_Str MSG_GRADIENT = _UxGT("Degradado"); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Degradado Total"); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Mestura Conmutada"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Mestura Cíclica"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Mestura de Degradado"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Degradado Inverso"); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Activar Ferr-V"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Inicio Ferr-V"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Fin Ferr-V"); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias Ferr-V"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reiniciar Ferr-V"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit mest. Ferr-V"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("Ferr-V reiniciadas"); + PROGMEM Language_Str MSG_START_Z = _UxGT("Inicio Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" Fin Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Xogos"); + PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + PROGMEM Language_Str MSG_MAZE = _UxGT("Labirinto"); #if LCD_HEIGHT >= 4 - // Up to 3 lines allowed - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "iniciar troco", "de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Agarde pola", "descarga do", "filamento")); + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Preme o botón para", "continuar impresión")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "comezar cambio", "de filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Introduza o", "filamento e", "faga click")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Prema o botón para", "quentar o bico")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Quentando bico", "Agarde, por favor...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Agarde pola", "descarga do", "filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Agarde pola", "carga do", "filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde para", "seguir co", "traballo")); - #else // LCD_HEIGHT < 4 - // Up to 2 lines allowed + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Agarde para", "purgar o filamento")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Prema para finalizar", "a purga do filamen.")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde a que", "se retome", "a impresión")); + #else + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premer para continuar")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Agarde...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Descargando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Introduza e click")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Prema para quentar")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Quentando...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Descargando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Cargando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Seguindo...")); - #endif // LCD_HEIGHT < 4 + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Prema para finalizar")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Retomando...")); + #endif + + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Controlador Actual"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Limiar Hibrido"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Orixe sen Sensores"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); + PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reiniciar"); + PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dentro:"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Reacción"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivel Eixe X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Tempo exc. Quent."); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Requentar"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Requentando..."); } From 1d81bb7a2b7692dff37d2a35dd547e6a8a25c49f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 6 Apr 2020 00:02:56 +0000 Subject: [PATCH 0111/1454] [cron] Bump distribution date (2020-04-06) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d24a9dbefa..cdeaeffd5e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-05" + #define STRING_DISTRIBUTION_DATE "2020-04-06" #endif /** From d6f39a69af1d5dbab09deeb8a35bcdc050488b83 Mon Sep 17 00:00:00 2001 From: Tor-p <63096807+Tor-p@users.noreply.github.com> Date: Mon, 6 Apr 2020 22:32:06 +0200 Subject: [PATCH 0112/1454] Fix G76 probe height / position (#17392) --- Marlin/Configuration_adv.h | 11 +---- Marlin/src/feature/probe_temp_comp.cpp | 10 ++-- Marlin/src/feature/probe_temp_comp.h | 32 ++++++------- Marlin/src/gcode/calibrate/G76_M871.cpp | 61 ++++++++++++------------- Marlin/src/inc/SanityCheck.h | 15 ++++++ buildroot/share/tests/rambo-tests | 2 +- 6 files changed, 66 insertions(+), 65 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7d1547c0d0..c715fe3332 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1600,18 +1600,11 @@ // Add additional compensation depending on hotend temperature // Note: this values cannot be calibrated and have to be set manually #if ENABLED(PROBE_TEMP_COMPENSATION) - // Max temperature that can be reached by heated bed. - // This is required only for the calibration process. - #define PTC_MAX_BED_TEMP BED_MAXTEMP - // Park position to wait for probe cooldown - #define PTC_PARK_POS_X 0.0F - #define PTC_PARK_POS_Y 0.0F - #define PTC_PARK_POS_Z 100.0F + #define PTC_PARK_POS { 0, 0, 100 } // Probe position to probe and wait for probe to reach target temperature - #define PTC_PROBE_POS_X 90.0F - #define PTC_PROBE_POS_Y 100.0F + #define PTC_PROBE_POS { 90, 100 } // Enable additional compensation using hotend temperature // Note: this values cannot be calibrated automatically but have to be set manually diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 6b787f420a..b773536a5d 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -29,11 +29,11 @@ ProbeTempComp temp_comp; -int16_t ProbeTempComp::z_offsets_probe[ProbeTempComp::cali_info_init[TSI_PROBE].measurements], // = {0} - ProbeTempComp::z_offsets_bed[ProbeTempComp::cali_info_init[TSI_BED].measurements]; // = {0} +int16_t ProbeTempComp::z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // = {0} + ProbeTempComp::z_offsets_bed[cali_info_init[TSI_BED].measurements]; // = {0} #if ENABLED(USE_TEMP_EXT_COMPENSATION) - int16_t ProbeTempComp::z_offsets_ext[ProbeTempComp::cali_info_init[TSI_EXT].measurements]; // = {0} + int16_t ProbeTempComp::z_offsets_ext[cali_info_init[TSI_EXT].measurements]; // = {0} #endif int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { @@ -44,9 +44,9 @@ int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { }; const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = { - ProbeTempComp::cali_info_init[TSI_PROBE], ProbeTempComp::cali_info_init[TSI_BED] + cali_info_init[TSI_PROBE], cali_info_init[TSI_BED] #if ENABLED(USE_TEMP_EXT_COMPENSATION) - , ProbeTempComp::cali_info_init[TSI_EXT] + , cali_info_init[TSI_EXT] #endif }; diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 2ed10eeb99..dff21b92ad 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -44,30 +44,28 @@ typedef struct { * Z-probes like the P.I.N.D.A V2 allow for compensation of * measurement errors/shifts due to changed temperature. */ + +static constexpr temp_calib_t cali_info_init[TSI_COUNT] = { + { 10, 5, 30, 30 + 10 * 5 }, // Probe + { 10, 5, 60, 60 + 10 * 5 }, // Bed + #if ENABLED(USE_TEMP_EXT_COMPENSATION) + { 20, 5, 180, 180 + 5 * 20 } // Extruder + #endif +}; + class ProbeTempComp { public: - static constexpr temp_calib_t cali_info_init[TSI_COUNT] = { - { 10, 5, 30, 30 + 10 * 5 }, // Probe - { 10, 5, 60, 60 + 10 * 5 }, // Bed - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - { 20, 5, 180, 180 + 5 * 20 } // Extruder - #endif - }; static const temp_calib_t cali_info[TSI_COUNT]; // Where to park nozzle to wait for probe cooldown - static constexpr float park_point_x = PTC_PARK_POS_X, - park_point_y = PTC_PARK_POS_Y, - park_point_z = PTC_PARK_POS_Z, - // XY coordinates of nozzle for probing the bed - measure_point_x = PTC_PROBE_POS_X, // Coordinates to probe - measure_point_y = PTC_PROBE_POS_Y; - //measure_point_x = 12.0f, // Coordinates to probe on MK52 magnetic heatbed - //measure_point_y = 7.3f; + static constexpr xyz_pos_t park_point = PTC_PARK_POS; - static constexpr int max_bed_temp = PTC_MAX_BED_TEMP, // Max temperature to avoid heating errors - probe_calib_bed_temp = max_bed_temp, // Bed temperature while calibrating probe + // XY coordinates of nozzle for probing the bed + static constexpr xy_pos_t measure_point = PTC_PROBE_POS; // Coordinates to probe + //measure_point = { 12.0f, 7.3f }; // Coordinates for the MK52 magnetic heatbed + + static constexpr int probe_calib_bed_temp = BED_MAXTEMP - 10, // Bed temperature while calibrating probe bed_calib_probe_temp = 30; // Probe temperature while calibrating bed static int16_t *sensor_z_offsets[TSI_COUNT], diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 4bc27b82f5..50b099bd1c 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -103,13 +103,19 @@ void GcodeSuite::G76() { return false; }; - auto g76_probe = [](const xy_pos_t &xypos) { + auto g76_probe = [](const TempSensorID sid, uint16_t &targ, const xy_pos_t &nozpos) { do_blocking_move_to_z(5.0); // Raise nozzle before probing - const float measured_z = probe.probe_at_point(xypos, PROBE_PT_NONE, 0, false); // verbose=0, probe_relative=false + const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_NONE, 0, false); // verbose=0, probe_relative=false if (isnan(measured_z)) SERIAL_ECHOLNPGM("!Received NAN. Aborting."); - else + else { SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + if (targ == cali_info_init[sid].start_temp) + temp_comp.prepare_new_calibration(measured_z); + else + temp_comp.push_back_new_measurement(sid, measured_z); + targ += cali_info_init[sid].temp_res; + } return measured_z; }; @@ -125,8 +131,9 @@ void GcodeSuite::G76() { // Synchronize with planner planner.synchronize(); - const xyz_pos_t parkpos = { temp_comp.park_point_x, temp_comp.park_point_y, temp_comp.park_point_z }; - const xy_pos_t ppos = { temp_comp.measure_point_x, temp_comp.measure_point_y }; + const xyz_pos_t parkpos = temp_comp.park_point, + probe_pos_xyz = temp_comp.measure_point + xyz_pos_t({ 0.0f, 0.0f, 0.5f }), + noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position if (do_bed_cal || do_probe_cal) { // Ensure park position is reachable @@ -135,7 +142,7 @@ void GcodeSuite::G76() { SERIAL_ECHOLNPGM("!Park"); else { // Ensure probe position is reachable - reachable = probe.can_reach(ppos); + reachable = probe.can_reach(probe_pos_xyz); if (!reachable) SERIAL_ECHOLNPGM("!Probe"); } @@ -149,8 +156,6 @@ void GcodeSuite::G76() { remember_feedrate_scaling_off(); - // Nozzle position based on probe position - const xy_pos_t noz_pos = ppos - probe.offset_xy; /****************************************** * Calibrate bed temperature offsets @@ -159,9 +164,13 @@ void GcodeSuite::G76() { // Report temperatures every second and handle heating timeouts millis_t next_temp_report = millis() + 1000; + auto report_targets = [&](const uint16_t tb, const uint16_t tp) { + SERIAL_ECHOLNPAIR("Target Bed:", tb, " Probe:", tp); + }; + if (do_bed_cal) { - uint16_t target_bed = temp_comp.cali_info_init[TSI_BED].start_temp, + uint16_t target_bed = cali_info_init[TSI_BED].start_temp, target_probe = temp_comp.bed_calib_probe_temp; SERIAL_ECHOLNPGM("Waiting for cooling."); @@ -176,7 +185,7 @@ void GcodeSuite::G76() { for (;;) { thermalManager.setTargetBed(target_bed); - SERIAL_ECHOLNPAIR("Target Bed:", target_bed, " Probe:", target_probe); + report_targets(target_bed, target_probe); // Park nozzle do_blocking_move_to(parkpos); @@ -188,21 +197,13 @@ void GcodeSuite::G76() { } // Move the nozzle to the probing point and wait for the probe to reach target temp - do_blocking_move_to_xy(noz_pos); + do_blocking_move_to(noz_pos_xyz); SERIAL_ECHOLNPGM("Waiting for probe heating."); while (thermalManager.degProbe() < target_probe) report_temps(next_temp_report); - const float measured_z = g76_probe(noz_pos); - if (isnan(measured_z)) break; - - if (target_bed == temp_comp.cali_info_init[TSI_BED].start_temp) - temp_comp.prepare_new_calibration(measured_z); - else - temp_comp.push_back_new_measurement(TSI_BED, measured_z); - - target_bed += temp_comp.cali_info_init[TSI_BED].temp_res; - if (target_bed > temp_comp.max_bed_temp) break; + const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz); + if (isnan(measured_z) || target_bed > BED_MAXTEMP - 10) break; } SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); @@ -231,7 +232,9 @@ void GcodeSuite::G76() { const uint16_t target_bed = temp_comp.probe_calib_bed_temp; thermalManager.setTargetBed(target_bed); - uint16_t target_probe = temp_comp.cali_info_init[TSI_PROBE].start_temp; + uint16_t target_probe = cali_info_init[TSI_PROBE].start_temp; + + report_targets(target_bed, target_probe); // Wait for heatbed to reach target temp and probe to cool below target temp wait_for_temps(target_bed, target_probe, next_temp_report); @@ -244,7 +247,7 @@ void GcodeSuite::G76() { bool timeout = false; for (;;) { // Move probe to probing point and wait for it to reach target temperature - do_blocking_move_to_xy(noz_pos); + do_blocking_move_to(noz_pos_xyz); SERIAL_ECHOLNPAIR("Waiting for probe heating. Bed:", target_bed, " Probe:", target_probe); const millis_t probe_timeout_ms = millis() + 900UL * 1000UL; @@ -257,16 +260,8 @@ void GcodeSuite::G76() { } if (timeout) break; - const float measured_z = g76_probe(noz_pos); - if (isnan(measured_z)) break; - - if (target_probe == temp_comp.cali_info_init[TSI_PROBE].start_temp) - temp_comp.prepare_new_calibration(measured_z); - else - temp_comp.push_back_new_measurement(TSI_PROBE, measured_z); - - target_probe += temp_comp.cali_info_init[TSI_PROBE].temp_res; - if (target_probe > temp_comp.cali_info_init[TSI_PROBE].end_temp) break; + const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz); + if (isnan(measured_z) || target_probe > cali_info_init[TSI_PROBE].end_temp) break; } SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 088ad098db..185f5c0b4d 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -491,6 +491,21 @@ #error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION. Please update Configuration_adv.h." #endif +/** + * Probe temp compensation requirements + */ +#if ENABLED(PROBE_TEMP_COMPENSATION) + #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) + #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array). Please update Configuration_adv.h." + #elif !defined(PTC_PARK_POS) + #error "PROBE_TEMP_COMPENSATION requires PTC_PARK_POS." + #elif defined(PTC_PROBE_POS_X) || defined(PTC_PROBE_POS_Y) + #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array). Please update Configuration_adv.h." + #elif !defined(PTC_PROBE_POS) + #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS." + #endif +#endif + /** * Marlin release, version and default string */ diff --git a/buildroot/share/tests/rambo-tests b/buildroot/share/tests/rambo-tests index 8092059627..57c363c3a4 100644 --- a/buildroot/share/tests/rambo-tests +++ b/buildroot/share/tests/rambo-tests @@ -50,7 +50,7 @@ opt_set GRID_MAX_POINTS_X 16 opt_set FANMUX0_PIN 53 opt_disable USE_WATCHDOG opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED \ + FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ From 966e0e4a77f6f62a173a2b08de73c25512b40072 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 6 Apr 2020 13:51:09 -0700 Subject: [PATCH 0113/1454] BTT002 release V1 uses STM32F407VGT6 (#17387) --- Marlin/src/core/boards.h | 2 +- buildroot/share/PlatformIO/boards/BigTree_Btt002.json | 10 +++++----- buildroot/share/tests/BIGTREE_BTT002-tests | 2 +- platformio.ini | 4 ++-- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 30c2d3eb87..c650d7ec75 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -319,7 +319,7 @@ #define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE #define BOARD_STEVAL_3DP001V1 4207 // STEVAL-3DP001V1 3D PRINTER BOARD #define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VE) +#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VG) #define BOARD_BTT_GTR_V1_0 4210 // BigTreeTech GTR v1.0 (STM32F407IGT) #define BOARD_LERDGE_K 4211 // Lerdge K (STM32F407ZG) #define BOARD_LERDGE_X 4212 // Lerdge X (STM32F407VE) diff --git a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json index 2fbf5ae8ac..8ef3b77ea8 100644 --- a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json +++ b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json @@ -15,22 +15,22 @@ ] ], "ldscript": "stm32f407xg.ld", - "mcu": "stm32f407vet6", + "mcu": "stm32f407vgt6", "variant": "BIGTREE_BTT002" }, "debug": { - "jlink_device": "STM32F407VE", + "jlink_device": "STM32F407VG", "openocd_target": "stm32f4x", "svd_path": "STM32F40x.svd" }, "frameworks": [ "arduino" ], - "name": "STM32F407VE (192k RAM. 512k Flash)", + "name": "STM32F407VG (192k RAM. 1024k Flash)", "upload": { "disable_flushing": false, "maximum_ram_size": 131072, - "maximum_size": 524288, + "maximum_size": 1048576, "protocol": "stlink", "protocols": [ "stlink", @@ -41,6 +41,6 @@ "use_1200bps_touch": false, "wait_for_upload_port": false }, - "url": "http://www.st.com/en/microcontrollers/stm32f407ve.html", + "url": "http://www.st.com/en/microcontrollers/stm32f407vg.html", "vendor": "Generic" } diff --git a/buildroot/share/tests/BIGTREE_BTT002-tests b/buildroot/share/tests/BIGTREE_BTT002-tests index 858957154d..1ab40123b5 100644 --- a/buildroot/share/tests/BIGTREE_BTT002-tests +++ b/buildroot/share/tests/BIGTREE_BTT002-tests @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F407VET6 BigTreeTech BTT002 +# Build tests for STM32F407VGT6 BigTreeTech BTT002 V1.0 # # exit on first failure diff --git a/platformio.ini b/platformio.ini index bf3dea01bc..f7fb31ec2e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -727,14 +727,14 @@ src_filter = ${common.default_src_filter} + monitor_speed = 250000 # -# BigTreeTech BTT002 (STM32F407VET6 ARM Cortex-M4) +# BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) # [env:BIGTREE_BTT002] platform = ststm32@5.6.0 board = BigTree_Btt002 platform_packages = framework-arduinoststm32@>=3.107,<4 build_flags = ${common.build_flags} - -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407VE\" + -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407VG\" -DTARGET_STM32F4 -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 -DHAVE_HWSERIAL2 -DHAVE_HWSERIAL3 From e1fc6f7e2508a73a760f8c1294f9aef405194880 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 7 Apr 2020 00:03:10 +0000 Subject: [PATCH 0114/1454] [cron] Bump distribution date (2020-04-07) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cdeaeffd5e..4d457a57df 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-06" + #define STRING_DISTRIBUTION_DATE "2020-04-07" #endif /** From 079644d01244a347c1535fac4beab61e5c1f853c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 8 Apr 2020 00:02:57 +0000 Subject: [PATCH 0115/1454] [cron] Bump distribution date (2020-04-08) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4d457a57df..b23b6d0743 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-07" + #define STRING_DISTRIBUTION_DATE "2020-04-08" #endif /** From 293a0997c9a7a84de37018581c1ccc6ef454c298 Mon Sep 17 00:00:00 2001 From: grauerfuchs <42082416+grauerfuchs@users.noreply.github.com> Date: Wed, 8 Apr 2020 13:53:28 -0400 Subject: [PATCH 0116/1454] Fix / optimize PCA9533 LED (Mightyboard) (#17381) --- Marlin/Configuration.h | 1 - Marlin/src/feature/leds/leds.cpp | 6 +- Marlin/src/feature/leds/pca9533.cpp | 127 ++++++++++++++++++ Marlin/src/feature/leds/pca9533.h | 59 ++++++++ .../variants/BIGTREE_SKR_PRO_1v1/variant.h | 2 +- buildroot/share/tests/DUE-tests | 2 +- buildroot/share/tests/rambo-tests | 2 +- platformio.ini | 11 +- 8 files changed, 197 insertions(+), 13 deletions(-) create mode 100644 Marlin/src/feature/leds/pca9533.cpp create mode 100644 Marlin/src/feature/leds/pca9533.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index f02e69ee5a..175a5fbef3 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2164,7 +2164,6 @@ //#define PCA9632 // Support for PCA9533 PWM LED driver -// https://github.com/mikeshub/SailfishRGB_LED //#define PCA9533 /** diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 995693ffc5..13d60fd5b7 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -39,7 +39,7 @@ #endif #if ENABLED(PCA9533) - #include + #include "pca9533.h" #endif #if ENABLED(LED_COLOR_PRESETS) @@ -72,7 +72,7 @@ void LEDLights::setup() { neo.init(); #endif #if ENABLED(PCA9533) - RGBinit(); + PCA9533_init(); #endif #if ENABLED(LED_USER_PRESET_STARTUP) set_default(); @@ -141,7 +141,7 @@ void LEDLights::set_color(const LEDColor &incol #endif #if ENABLED(PCA9533) - RGBsetColor(incol.r, incol.g, incol.b, true); + PCA9533_setColor(incol.r, incol.g, incol.b); #endif #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) diff --git a/Marlin/src/feature/leds/pca9533.cpp b/Marlin/src/feature/leds/pca9533.cpp new file mode 100644 index 0000000000..82bdaf6665 --- /dev/null +++ b/Marlin/src/feature/leds/pca9533.cpp @@ -0,0 +1,127 @@ +/* + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * PCA9533 LED controller driver (MightyBoard, FlashForge Creator Pro, etc.) + * by @grauerfuchs - 1 Apr 2020 + */ +#include "../../inc/MarlinConfig.h" + +#if ENABLED(PCA9533) + +#include "pca9533.h" +#include + +void PCA9533_init() { + Wire.begin(); + PCA9533_reset(); +} + +static void PCA9533_writeAllRegisters(uint8_t psc0, uint8_t pwm0, uint8_t psc1, uint8_t pwm1, uint8_t ls0){ + uint8_t data[6] = { PCA9533_REG_PSC0 | PCA9533_REGM_AI, psc0, pwm0, psc1, pwm1, ls0 }; + Wire.beginTransmission(PCA9533_Addr >> 1); + Wire.write(data, 6); + Wire.endTransmission(); + delayMicroseconds(1); +} + +static void PCA9533_writeRegister(uint8_t reg, uint8_t val){ + uint8_t data[2] = { reg, val }; + Wire.beginTransmission(PCA9533_Addr >> 1); + Wire.write(data, 2); + Wire.endTransmission(); + delayMicroseconds(1); +} + +// Reset (clear) all registers +void PCA9533_reset() { + PCA9533_writeAllRegisters(0, 0, 0, 0, 0); +} + +// Turn all LEDs off +void PCA9533_setOff() { + PCA9533_writeRegister(PCA9533_REG_SEL, 0); +} + +void PCA9533_setColor(uint8_t red, uint8_t green, uint8_t blue) { + uint8_t r_pwm0 = 0; // Register data - PWM value + uint8_t r_pwm1 = 0; // Register data - PWM value + + uint8_t op_g = 0, op_r = 0, op_b = 0; // Opcodes - Green, Red, Blue + + // Light theory! GREEN takes priority because + // it's the most visible to the human eye. + if (green == 0) op_g = PCA9533_LED_OP_OFF; + else if (green == 255) op_g = PCA9533_LED_OP_ON; + else { r_pwm0 = green; op_g = PCA9533_LED_OP_PWM0; } + + // RED + if (red == 0) op_r = PCA9533_LED_OP_OFF; + else if (red == 255) op_r = PCA9533_LED_OP_ON; + else if (r_pwm0 == 0 || r_pwm0 == red) { + r_pwm0 = red; op_r = PCA9533_LED_OP_PWM0; + } + else { + r_pwm1 = red; op_r = PCA9533_LED_OP_PWM1; + } + + // BLUE + if (blue == 0) op_b = PCA9533_LED_OP_OFF; + else if (blue == 255) op_b = PCA9533_LED_OP_ON; + else if (r_pwm0 == 0 || r_pwm0 == blue) { + r_pwm0 = blue; op_b = PCA9533_LED_OP_PWM0; + } + else if (r_pwm1 == 0 || r_pwm1 == blue) { + r_pwm1 = blue; op_b = PCA9533_LED_OP_PWM1; + } + else { + /** + * Conflict. 3 values are requested but only 2 channels exist. + * G is on channel 0 and R is on channel 1, so work from there. + * Find the closest match, average the values, then use the free channel. + */ + uint8_t dgb = ABS(green - blue), + dgr = ABS(green - red), + dbr = ABS(blue - red); + if (dgb < dgr && dgb < dbr) { // Mix with G on channel 0. + op_b = PCA9533_LED_OP_PWM0; + r_pwm0 = uint8_t(((uint16_t)green + (uint16_t)blue) / 2); + } + else if (dbr <= dgr && dbr <= dgb) { // Mix with R on channel 1. + op_b = PCA9533_LED_OP_PWM1; + r_pwm1 = uint8_t(((uint16_t)red + (uint16_t)blue) / 2); + } + else { // Mix R+G on 0 and put B on 1. + op_r = PCA9533_LED_OP_PWM0; + r_pwm0 = uint8_t(((uint16_t)green + (uint16_t)red) / 2); + op_b = PCA9533_LED_OP_PWM1; + r_pwm1 = blue; + } + } + + // Write the changes to the hardware + PCA9533_writeAllRegisters(0, r_pwm0, 0, r_pwm1, + (op_g << PCA9533_LED_OFS_GRN) | (op_r << PCA9533_LED_OFS_RED) | (op_b << PCA9533_LED_OFS_BLU) + ); +} + +#endif // PCA9533 diff --git a/Marlin/src/feature/leds/pca9533.h b/Marlin/src/feature/leds/pca9533.h new file mode 100644 index 0000000000..a134ca15fd --- /dev/null +++ b/Marlin/src/feature/leds/pca9533.h @@ -0,0 +1,59 @@ +/* + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/* + * Driver for the PCA9533 LED controller found on the MightyBoard + * used by FlashForge Creator Pro, MakerBot, etc. + * Written 2020 APR 01 by grauerfuchs + */ +#include + +#define ENABLE_I2C_PULLUPS + +// Chip address (for Wire) +#define PCA9533_Addr 0xC4 + +// Control registers +#define PCA9533_REG_READ 0x00 +#define PCA9533_REG_PSC0 0x01 +#define PCA9533_REG_PWM0 0x02 +#define PCA9533_REG_PSC1 0x03 +#define PCA9533_REG_PWM1 0x04 +#define PCA9533_REG_SEL 0x05 +#define PCA9533_REGM_AI 0x10 + +// LED selector operation +#define PCA9533_LED_OP_OFF 0B00 +#define PCA9533_LED_OP_ON 0B01 +#define PCA9533_LED_OP_PWM0 0B10 +#define PCA9533_LED_OP_PWM1 0B11 + +// Select register bit offsets for LED colors +#define PCA9533_LED_OFS_RED 0 +#define PCA9533_LED_OFS_GRN 2 +#define PCA9533_LED_OFS_BLU 4 + +void PCA9533_init(); +void PCA9533_reset(); +void PCA9533_setColor(uint8_t red, uint8_t green, uint8_t blue); +void PCA9533_setOff(); diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h index 5ff2ea5768..0eab1abe53 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h @@ -234,7 +234,7 @@ extern "C" { // On-board LED pin number #define LED_BUILTIN PA7 -//#define LED_GREEN LED_BUILTIN should be defined here but omitted to avoid redefinition in SailfishRGB_LED +#define LED_GREEN LED_BUILTIN // Below SPI and I2C definitions already done in the core // Could be redefined here if differs from the default one diff --git a/buildroot/share/tests/DUE-tests b/buildroot/share/tests/DUE-tests index cfce93a92e..0d9b95e1cf 100755 --- a/buildroot/share/tests/DUE-tests +++ b/buildroot/share/tests/DUE-tests @@ -16,7 +16,7 @@ opt_set FANMUX0_PIN 53 opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING \ EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ - BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ + BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_DISTANCE_MM FILAMENT_RUNOUT_SENSOR \ AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ diff --git a/buildroot/share/tests/rambo-tests b/buildroot/share/tests/rambo-tests index 57c363c3a4..7fab4fc6ca 100644 --- a/buildroot/share/tests/rambo-tests +++ b/buildroot/share/tests/rambo-tests @@ -53,7 +53,7 @@ opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TE FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ - BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ + BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS \ diff --git a/platformio.ini b/platformio.ini index f7fb31ec2e..2ba1c5c1f3 100644 --- a/platformio.ini +++ b/platformio.ini @@ -33,7 +33,6 @@ lib_deps = LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/0.8.0.zip SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip - SailfishRGB_LED=https://github.com/mikeshub/SailfishRGB_LED/archive/master.zip SlowSoftI2CMaster=https://github.com/mikeshub/SlowSoftI2CMaster/archive/master.zip # Globally defined properties @@ -623,7 +622,7 @@ build_flags = ${common.build_flags} build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py -lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial +lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial src_filter = ${common.default_src_filter} + # @@ -639,7 +638,7 @@ build_flags = ${common.build_flags} -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial +lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial src_filter = ${common.default_src_filter} + @@ -679,7 +678,7 @@ build_flags = ${common.build_flags} -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial +lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial src_filter = ${common.default_src_filter} + # @@ -742,7 +741,7 @@ build_flags = ${common.build_flags} -DPIN_SERIAL2_TX=PD_5 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -lib_ignore = Adafruit NeoPixel, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster +lib_ignore = Adafruit NeoPixel, SailfishLCD, SlowSoftI2CMaster src_filter = ${common.default_src_filter} + # @@ -780,7 +779,7 @@ lib_deps = ${common.lib_deps} ESP3DLib=https://github.com/luc-github/ESP3DLib.git arduinoWebSockets=https://github.com/Links2004/arduinoWebSockets.git ESP32SSDP=https://github.com/luc-github/ESP32SSDP.git -lib_ignore = LiquidCrystal, LiquidTWI2, SailfishLCD, SailfishRGB_LED, ESPAsyncTCP +lib_ignore = LiquidCrystal, LiquidTWI2, SailfishLCD, ESPAsyncTCP src_filter = ${common.default_src_filter} + upload_speed = 115200 #upload_port = marlinesp.local From d6badb77a41b79c3b5a8ff40cc87338c413bccb2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 6 Apr 2020 15:39:34 -0500 Subject: [PATCH 0117/1454] Clean up whitespace --- Marlin/Configuration_adv.h | 4 ---- Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h | 2 +- .../lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp | 2 +- Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h | 2 +- Marlin/src/lcd/extui/ui_api.h | 2 +- 5 files changed, 4 insertions(+), 8 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index c715fe3332..d06fe732a4 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -340,7 +340,6 @@ * * The fan turns on automatically whenever any driver is enabled and turns * off (or reduces to idle speed) shortly after drivers are turned off. - * */ //#define USE_CONTROLLER_FAN #if ENABLED(USE_CONTROLLER_FAN) @@ -1060,9 +1059,6 @@ * during SD printing. If the recovery file is found at boot time, present * an option on the LCD screen to continue the print from the last-known * point in the file. - * - * If the machine reboots when resuming a print you may need to replace or - * reformat the SD card. (Bad sectors delay startup triggering the watchdog.) */ //#define POWER_LOSS_RECOVERY #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index b5b0f22e11..1780c587e1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -149,7 +149,7 @@ #define CLCD_SPI_CS BTN_EN1 #define CLCD_MOD_RESET BTN_EN2 - + #if MB(EINSY_RAMBO, EINSY_RETRO) && DISABLED(SDSUPPORT) #define CLCD_SPI_EXTRA_CS SDSS #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp index f0b5dd887b..5fbb43cdb5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp @@ -39,7 +39,7 @@ void PreheatMenu::onRedraw(draw_mode_t what) { #define GRID_ROWS 3 #define GRID_COLS 2 - + if (what & FOREGROUND) { CommandProcessor cmd; cmd.cmd(COLOR_RGB(bg_text_enabled)) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h index e2770d8116..f8b58098f5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h @@ -129,7 +129,7 @@ namespace Theme { #if ENABLED(TOUCH_UI_ROYAL_THEME) constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26); constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.13); - constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.10); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.10); #else constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.5); constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.37); diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 43e337e877..2ed602c32c 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -141,7 +141,7 @@ namespace ExtUI { void setMeshPoint(const xy_uint8_t &pos, const float zval); void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); inline void onMeshUpdate(const xy_int8_t &pos, const float zval) { onMeshUpdate(pos.x, pos.y, zval); } - + typedef enum : unsigned char { PROBE_START, PROBE_FINISH } probe_state_t; void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state); inline void onMeshUpdate(const xy_int8_t &pos, probe_state_t state) { onMeshUpdate(pos.x, pos.y, state); } From 3ea23712eb1acff7dc25b29b3f4778aa3beb5db8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 8 Apr 2020 14:16:50 -0500 Subject: [PATCH 0118/1454] Fix stepper DAC compile Fixes #17438 --- Marlin/src/feature/dac/stepper_dac.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index c8c1cb2494..15f35d91d7 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -29,6 +29,7 @@ #if ENABLED(DAC_STEPPER_CURRENT) #include "stepper_dac.h" +#include "../../MarlinCore.h" // for SP_X_LBL... bool dac_present = false; constexpr xyze_uint8_t dac_order = DAC_STEPPER_ORDER; @@ -85,15 +86,12 @@ void dac_current_set_percents(xyze_uint8_t &pct) { void dac_print_values() { if (!dac_present) return; - SERIAL_ECHO_MSG("Stepper current values in % (Amps):"); SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")") - SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")") - SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")") - SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")") - ); + SERIAL_ECHOPAIR_P( SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); + SERIAL_ECHOPAIR_P( SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); + SERIAL_ECHOPAIR_P( SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); + SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); } void dac_commit_eeprom() { From a1523d64199b69878d9208c335eaca293260077e Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Wed, 8 Apr 2020 22:00:31 +0200 Subject: [PATCH 0119/1454] Fix: const needed for operator* (#17443) --- Marlin/src/module/planner.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 2de46373b2..4ad7a79431 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2885,7 +2885,7 @@ void Planner::set_max_acceleration(const uint8_t axis, float targetValue) { const xyze_float_t &max_acc_edit_scaled = max_accel_edit; #else constexpr xyze_float_t max_accel_edit = DEFAULT_MAX_ACCELERATION; - constexpr xyze_float_t max_acc_edit_scaled = max_accel_edit * 2; + const xyze_float_t max_acc_edit_scaled = max_accel_edit * 2; #endif limit_and_warn(targetValue, axis, PSTR("Acceleration"), max_acc_edit_scaled); #endif @@ -2902,7 +2902,7 @@ void Planner::set_max_feedrate(const uint8_t axis, float targetValue) { const xyze_float_t &max_fr_edit_scaled = max_fr_edit; #else constexpr xyze_float_t max_fr_edit = DEFAULT_MAX_FEEDRATE; - constexpr xyze_float_t max_fr_edit_scaled = max_fr_edit * 2; + const xyze_float_t max_fr_edit_scaled = max_fr_edit * 2; #endif limit_and_warn(targetValue, axis, PSTR("Feedrate"), max_fr_edit_scaled); #endif From 556406a127c99d3d4501a24164b6c05b5e5a2bbb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 9 Apr 2020 00:02:53 +0000 Subject: [PATCH 0120/1454] [cron] Bump distribution date (2020-04-09) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b23b6d0743..75b7682497 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-08" + #define STRING_DISTRIBUTION_DATE "2020-04-09" #endif /** From 71a4ab3331bf40b985ae9ed214459bc12d0679dd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 9 Apr 2020 12:28:09 -0500 Subject: [PATCH 0121/1454] Add "Settings Stored" message --- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/module/configuration_store.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 2037d0c928..2d5ae84ed3 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -325,6 +325,7 @@ namespace Language_en { PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: EEPROM Index"); PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: EEPROM Version"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Media Update"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reset Printer"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Refresh"); diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index a2beb322f9..0211c303eb 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -1361,6 +1361,8 @@ void MarlinSettings::postprocess() { store_mesh(ubl.storage_slot); #endif + if (!eeprom_error) LCD_MESSAGEPGM(MSG_SETTINGS_STORED); + #if ENABLED(EXTENSIBLE_UI) ExtUI::onConfigurationStoreWritten(!eeprom_error); #endif From 3645e59893825133924a8af1f6ad5773d21f7f15 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 9 Apr 2020 12:30:43 -0500 Subject: [PATCH 0122/1454] Minor style tweaks --- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 11 +++-------- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 ++-- 2 files changed, 5 insertions(+), 10 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index d982bd6268..2ae5f25271 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -79,21 +79,16 @@ static void debug_rw(const bool write, int &pos, const uint8_t *value, const siz PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); SERIAL_CHAR(' '); serialprintPGM(rw_str); - SERIAL_ECHOPAIR("_data(", pos); - SERIAL_ECHOPAIR(",", (int)value); - SERIAL_ECHOPAIR(",", (int)size); - SERIAL_ECHOLNPGM(", ...)"); + SERIAL_ECHOLNPAIR("_data(", pos, ",", int(value), ",", int(size), ", ...)"); if (total) { SERIAL_ECHOPGM(" f_"); serialprintPGM(rw_str); - SERIAL_ECHOPAIR("()=", (int)s); - SERIAL_ECHOPAIR("\n size=", size); - SERIAL_ECHOPGM("\n bytes_"); + SERIAL_ECHOPAIR("()=", int(s), "\n size=", int(size), "\n bytes_"); serialprintPGM(write ? PSTR("written=") : PSTR("read=")); SERIAL_ECHOLN(total); } else - SERIAL_ECHOLNPAIR(" f_lseek()=", (int)s); + SERIAL_ECHOLNPAIR(" f_lseek()=", int(s)); } // File function return codes for type FRESULT. This goes away soon, but diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 940b4eaeb4..d451f7246f 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -451,8 +451,8 @@ SERIAL_ECHO(g29_pos.y); SERIAL_ECHOLNPGM(").\n"); } - const xy_pos_t near = g29_pos + probe.offset_xy; - probe_entire_mesh(near, parser.seen('T'), parser.seen('E'), parser.seen('U')); + const xy_pos_t near_probe_xy = g29_pos + probe.offset_xy; + probe_entire_mesh(near_probe_xy, parser.seen('T'), parser.seen('E'), parser.seen('U')); report_current_position(); probe_deployed = true; From 5158106c12faf961eb886cbc6348060ce093c340 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Thu, 9 Apr 2020 20:35:32 +0200 Subject: [PATCH 0123/1454] Update Spanish translation (#17406) --- Marlin/src/lcd/language/language_es.h | 106 +++++++++++++++++++------- 1 file changed, 80 insertions(+), 26 deletions(-) diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 12d487b35b..54e05a1c41 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -29,15 +29,14 @@ * */ -#define DISPLAY_CHARSET_ISO10646_1 - namespace Language_es { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; PROGMEM Language_Str LANGUAGE = _UxGT("Spanish"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" lista"); + PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Lista"); + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); PROGMEM Language_Str MSG_YES = _UxGT("SI"); PROGMEM Language_Str MSG_NO = _UxGT("NO"); PROGMEM Language_Str MSG_BACK = _UxGT("Atrás"); @@ -87,6 +86,7 @@ namespace Language_es { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Precalentar ") PREHEAT_2_LABEL _UxGT(" Ajuste"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Precalen. Personali."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Enfriar"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Láser Apagado"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Láser Encendido"); @@ -137,9 +137,9 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Cama"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT ("Hotend Temp"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Cama"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Fusor"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Fusor"); PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Mallado"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Mallado perso."); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Ajuste fino Mallado"); @@ -172,7 +172,7 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Salida Mapa mallado"); PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Salida para el host"); PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Salida para CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Off Printer Backup"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Cópia de seg. ext"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Salida Info. UBL"); PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidad de relleno"); PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Relleno manual"); @@ -186,8 +186,8 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Huecos de memoria"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Mallado cama"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Guardar Mallado cama"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Mallado %i Cargado"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Mallado %i Guardado"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Mall. %i Carga."); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Mall. %i Guard."); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sin guardar"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Error: Guardar UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Error: Restaurar UBL"); @@ -195,12 +195,12 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Parado"); PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crear Mallado Frío"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Relleno inteligente"); + PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Relleno intelig."); PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Validar Mallado"); PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ajustar Fino Todo"); PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Validar Mallado"); PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ajustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Guardar Mallado cama"); + PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Guardar Mall. cama"); PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Control LED"); PROGMEM Language_Str MSG_LEDS = _UxGT("Luzes"); @@ -237,25 +237,57 @@ namespace Language_es { PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Boquilla ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Boquilla Aparcada"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Boquilla en Espera"); PROGMEM Language_Str MSG_BED = _UxGT("Cama"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Recinto"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Ventilador"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Ventilador ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Ext. ventilador"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Ext. ventilador ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Vent. almacenado ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Ext. ventil."); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Ext. ventil. ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidad en reposo"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidad Activa"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Periodo de reposo"); PROGMEM Language_Str MSG_FLOW = _UxGT("Flujo"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flujo ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Factor"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temperatura Auto."); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Encender"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apagar"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Seleccionar"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seleccionar *"); PROGMEM Language_Str MSG_ACC = _UxGT("Aceleración"); + PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desviación de Unión"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidad"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accel"); PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; @@ -275,8 +307,8 @@ namespace Language_es { PROGMEM Language_Str MSG_MOTION = _UxGT("Movimiento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diámetro Fil."); + PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diámetro Fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carga mm"); PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avance K"); @@ -286,6 +318,9 @@ namespace Language_es { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar EEPROM"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Rest. fábrica"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: Índice EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versión EEPROM"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetear Impresora"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); @@ -300,9 +335,14 @@ namespace Language_es { PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reiniciar"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancelar"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Listo"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Retroceder"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceder"); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Reanudar impresión"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Detener impresión"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimiendo Objeto"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Recuper. por interr."); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Imprim. desde SD/USB"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD/USB no presente"); @@ -311,6 +351,7 @@ namespace Language_es { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimiendo..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impresión cancelada"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Impresión Completada"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sin movimiento"); PROGMEM Language_Str MSG_KILLED = _UxGT("MUERTA"); PROGMEM Language_Str MSG_STOPPED = _UxGT("DETENIDA"); @@ -327,9 +368,8 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purgar longitud"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Herramienta"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Aumentar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prime Speed"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Vel. de Cebado"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Vel. de retracción"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Colocar boquilla"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar filamento *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar filamento"); @@ -362,8 +402,11 @@ namespace Language_es { PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Subir TouchMI"); PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Subir Sonda Z"); PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Bajar Sonda Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Origen %s%s%s Primero"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Origen %s%s%s Prim."); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desfase Sonda"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desfase Sonda X"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desfase Sonda Y"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Sonda Z"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); @@ -419,9 +462,11 @@ namespace Language_es { PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudios"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Vig. Fuga Térm.: OFF"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Vig. Fuga Térm.: ON"); + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz cabina"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo cabina"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); #if LCD_WIDTH >= 20 @@ -437,6 +482,7 @@ namespace Language_es { PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Más larga"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); #endif + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp. Mínima"); PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fuente alimentación"); @@ -501,7 +547,7 @@ namespace Language_es { PROGMEM Language_Str MSG_START_Z = _UxGT("Inicio Z:"); PROGMEM Language_Str MSG_END_Z = _UxGT(" Fin Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Games"); + PROGMEM Language_Str MSG_GAMES = _UxGT("Juegos"); PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); @@ -515,6 +561,7 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Pulse el botón para", "calentar la boquilla")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Calentando boquilla", "Espere por favor...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Espere para", "liberar el filamento")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Espere para", "cargar el filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Espere para", "purgar el filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Pulse para finalizar", "la purga de filamen.")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impresora", "para reanudar...")); @@ -531,17 +578,24 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Pulse para finalizar")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reanudando...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Amperaje Controlador"); PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Límite Hibrido"); PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Origen sin sensores"); PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reiniciar"); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dentro:"); - - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivel Eje X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("T. de esp. Calent."); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Recalentar"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Recalentando..."); } From 397fa59eee70290dd0f0b16227f3f34ad75f42cf Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Thu, 9 Apr 2020 22:58:45 +0200 Subject: [PATCH 0124/1454] Sort out USBComposite for STM32F1 confusion (#17400) --- platformio.ini | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 2ba1c5c1f3..d072ae4cc9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -319,7 +319,6 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -350,7 +349,6 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -417,6 +415,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI debug_tool = stlink upload_protocol = stlink From dbdfe61644df845a4bdebb62b4b7d1cd51fc4a07 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Thu, 9 Apr 2020 15:00:25 -0600 Subject: [PATCH 0125/1454] Fix and improve FTDI Eve Touch UI (#17426) --- .../screens/bed_mesh_screen.cpp | 133 +++++++++++------- .../ftdi_eve_touch_ui/screens/boot_screen.cpp | 2 +- .../lib/ftdi_eve_touch_ui/screens/screens.h | 4 +- .../screens/status_screen.cpp | 3 +- .../screens/touch_calibration_screen.cpp | 6 +- 5 files changed, 92 insertions(+), 56 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp index bce39a6ec0..ff954204c0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -43,41 +43,33 @@ using namespace ExtUI; #define GRID_COLS 5 #define GRID_ROWS 5 - #define MESH_POS BTN_POS(2,1), BTN_SIZE(4,5) - #define Z_LABEL_POS BTN_POS(1,3), BTN_SIZE(1,1) - #define Z_VALUE_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define WAIT_POS BTN_POS(1,3), BTN_SIZE(2,2) - #define BACK_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define MESH_POS BTN_POS(1,1), BTN_SIZE(3,5) + #define Z_LABEL_POS BTN_POS(4,2), BTN_SIZE(2,1) + #define Z_VALUE_POS BTN_POS(4,3), BTN_SIZE(2,1) + #define WAIT_POS BTN_POS(4,2), BTN_SIZE(2,2) + #define BACK_POS BTN_POS(4,5), BTN_SIZE(2,1) #endif -void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts) { - CommandProcessor cmd; +void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max) { + constexpr uint8_t rows = GRID_MAX_POINTS_Y; + constexpr uint8_t cols = GRID_MAX_POINTS_X; - #define TRANSFORM_2(X,Y,Z) (X), (Y) // No transform - #define TRANSFORM_1(X,Y,Z) TRANSFORM_2((X) + (Y) * slant, (Y) - (Z), 0) // Perspective - #define TRANSFORM(X,Y,Z) TRANSFORM_1(float(X)/(cols-1) - 0.5, float(Y)/(rows-1) - 0.5, (Z)) // Normalize + #define VALUE(X,Y) (data ? data[X][Y] : 0) + #define ISVAL(X,Y) (data ? !isnan(VALUE(X,Y)) : true) + #define HEIGHT(X,Y) (ISVAL(X,Y) ? (VALUE(X,Y) - val_min) * scale_z : 0) - constexpr uint8_t rows = GRID_MAX_POINTS_Y; - constexpr uint8_t cols = GRID_MAX_POINTS_X; - const float slant = 0.5; - const float bounds_min[] = {TRANSFORM(0 ,0 ,0)}; - const float bounds_max[] = {TRANSFORM(cols,rows,0)}; - const float scale_x = float(w)/(bounds_max[0] - bounds_min[0]); - const float scale_y = float(h)/(bounds_max[1] - bounds_min[1]); - const float center_x = x + w/2; - const float center_y = y + h/2; + // Compute the mean, min and max for the points float val_mean = 0; float val_max = -INFINITY; float val_min = INFINITY; uint8_t val_cnt = 0; - if (opts & USE_AUTOSCALE) { - // Compute the mean + if (data && (opts & USE_AUTOSCALE)) { for (uint8_t y = 0; y < rows; y++) { for (uint8_t x = 0; x < cols; x++) { - const float val = data[x][y]; - if (!isnan(val)) { + if (ISVAL(x,y)) { + const float val = VALUE(x,y); val_mean += val; val_max = max(val_max, val); val_min = min(val_min, val); @@ -85,27 +77,56 @@ void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI:: } } } - if (val_cnt) { - val_mean /= val_cnt; - val_min -= val_mean; - val_max -= val_mean; - } else { - val_mean = 0; - val_min = 0; - val_max = 0; - } + } + if (val_cnt) { + val_mean /= val_cnt; + } else { + val_mean = 0; + val_min = 0; + val_max = 0; } - const float scale_z = ((val_max == val_min) ? 1 : 1/(val_max - val_min)) * 0.1; + const float scale_z = ((val_max == val_min) ? 1 : 1/(val_max - val_min)) * autoscale_max; - #undef TRANSFORM_2 - #define TRANSFORM_2(X,Y,Z) center_x + (X) * scale_x, center_y + (Y) * scale_y // Scale and position - #define VALUE(X,Y) ((data && ISVAL(X,Y)) ? data[X][Y] : 0) - #define ISVAL(X,Y) (data ? !isnan(data[X][Y]) : true) - #define HEIGHT(X,Y) (VALUE(X,Y) * scale_z) + // These equations determine the appearance of the grid on the screen. - uint16_t basePointSize = min(scale_x,scale_y) / max(cols,rows); + #define TRANSFORM_5(X,Y,Z) (X), (Y) // No transform + #define TRANSFORM_4(X,Y,Z) TRANSFORM_5((X)/(Z),(Y)/-(Z), 0) // Perspective + #define TRANSFORM_3(X,Y,Z) TRANSFORM_4((X), (Z), (Y)) // Swap Z and Y + #define TRANSFORM_2(X,Y,Z) TRANSFORM_3((X), (Y) + 2.5, (Z) - 1) // Translate + #define TRANSFORM(X,Y,Z) TRANSFORM_2(float(X)/(cols-1) - 0.5, float(Y)/(rows-1) - 0.5, (Z)) // Normalize + // Compute the bounding box for the grid prior to scaling. Do this at compile-time by + // transforming the four corner points via the transformation equations and finding + // the min and max for each axis. + + constexpr float bounds[][3] = {{TRANSFORM(0 , 0 , 0)}, + {TRANSFORM(cols-1, 0 , 0)}, + {TRANSFORM(0 , rows-1, 0)}, + {TRANSFORM(cols-1, rows-1, 0)}}; + #define APPLY(FUNC, AXIS) FUNC(FUNC(bounds[0][AXIS], bounds[1][AXIS]), FUNC(bounds[2][AXIS], bounds[3][AXIS])) + constexpr float grid_x = APPLY(min,0); + constexpr float grid_y = APPLY(min,1); + constexpr float grid_w = APPLY(max,0) - grid_x; + constexpr float grid_h = APPLY(max,1) - grid_y; + constexpr float grid_cx = grid_x + grid_w/2; + constexpr float grid_cy = grid_y + grid_h/2; + + // Figure out scale and offset such that the grid fits within the rectangle given by (x,y,w,h) + + const float scale_x = float(w)/grid_w; + const float scale_y = float(h)/grid_h; + const float center_x = x + w/2; + const float center_y = y + h/2; + + #undef TRANSFORM_5 + #define TRANSFORM_5(X,Y,Z) center_x + (X - grid_cx) * scale_x, center_y + (Y - grid_cy) * scale_y // Fit to bounds + + // Draw the grid + + const uint16_t basePointSize = min(w,h) / max(cols,rows); + + CommandProcessor cmd; cmd.cmd(SAVE_CONTEXT()) .cmd(VERTEX_FORMAT(0)) .cmd(TAG_MASK(false)) @@ -126,13 +147,15 @@ void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI:: } if (opts & USE_POINTS) { + const float sq_min = sq(val_min - val_mean); + const float sq_max = sq(val_max - val_mean); cmd.cmd(POINT_SIZE(basePointSize * 2)); cmd.cmd(BEGIN(POINTS)); for (uint8_t x = 0; x < cols; x++) { if (ISVAL(x,y)) { if (opts & USE_COLORS) { const float val_dev = VALUE(x, y) - val_mean; - const uint8_t neg_byte = sq(val_dev) / sq(val_dev < 0 ? val_min : val_max) * 0xFF; + const uint8_t neg_byte = sq(val_dev) / (val_dev < 0 ? sq_min : sq_max) * 0xFF; const uint8_t pos_byte = 255 - neg_byte; cmd.cmd(COLOR_RGB(pos_byte, pos_byte, 0xFF)); } @@ -164,11 +187,12 @@ void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI:: if (opts & USE_HIGHLIGHT) { const uint8_t tag = screen_data.BedMeshScreen.highlightedTag; uint8_t x, y; - tagToPoint(tag, x, y); - cmd.cmd(COLOR_A(128)) - .cmd(POINT_SIZE(basePointSize * 6)) - .cmd(BEGIN(POINTS)) - .tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + if (tagToPoint(tag, x, y)) { + cmd.cmd(COLOR_A(128)) + .cmd(POINT_SIZE(basePointSize * 6)) + .cmd(BEGIN(POINTS)) + .tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } } cmd.cmd(END()); cmd.cmd(RESTORE_CONTEXT()); @@ -178,9 +202,11 @@ uint8_t BedMeshScreen::pointToTag(uint8_t x, uint8_t y) { return y * (GRID_MAX_POINTS_X) + x + 10; } -void BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { +bool BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { + if (tag < 10) return false; x = (tag - 10) % (GRID_MAX_POINTS_X); y = (tag - 10) / (GRID_MAX_POINTS_X); + return true; } void BedMeshScreen::onEntry() { @@ -217,6 +243,9 @@ void BedMeshScreen::drawHighlightedPointValue() { } void BedMeshScreen::onRedraw(draw_mode_t what) { + #define _INSET_POS(x,y,w,h) x + min(w,h)/10, y + min(w,h)/10, w - min(w,h)/5, h - min(w,h)/5 + #define INSET_POS(pos) _INSET_POS(pos) + if (what & BACKGROUND) { CommandProcessor cmd; cmd.cmd(CLEAR_COLOR_RGB(bg_color)) @@ -224,16 +253,20 @@ void BedMeshScreen::onRedraw(draw_mode_t what) { // Draw the shadow and tags cmd.cmd(COLOR_RGB(0x444444)); - BedMeshScreen::drawMesh(MESH_POS, nullptr, USE_POINTS | USE_TAGS); + BedMeshScreen::drawMesh(INSET_POS(MESH_POS), nullptr, USE_POINTS | USE_TAGS); cmd.cmd(COLOR_RGB(bg_text_enabled)); } if (what & FOREGROUND) { + constexpr float autoscale_max_amplitude = 0.03; const bool levelingFinished = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; + const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); if (levelingFinished) drawHighlightedPointValue(); - BedMeshScreen::drawMesh(MESH_POS, ExtUI::getMeshArray(), - USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0)); + BedMeshScreen::drawMesh(INSET_POS(MESH_POS), ExtUI::getMeshArray(), + USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0), + autoscale_max_amplitude * levelingProgress + ); } } @@ -243,7 +276,7 @@ bool BedMeshScreen::onTouchStart(uint8_t tag) { } bool BedMeshScreen::onTouchEnd(uint8_t tag) { - switch(tag) { + switch (tag) { case 1: GOTO_PREVIOUS(); return true; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp index 5e022b58e7..fcb0b67f88 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp @@ -68,10 +68,10 @@ void BootScreen::onIdle() { InterfaceSettingsScreen::failSafeSettings(); StatusScreen::loadBitmaps(); + StatusScreen::setStatusMessage(GET_TEXT_F(WELCOME_MSG)); GOTO_SCREEN(TouchCalibrationScreen); current_screen.forget(); PUSH_SCREEN(StatusScreen); - StatusScreen::setStatusMessage(GET_TEXT_F(WELCOME_MSG)); } else { if (!UIFlashStorage::is_valid()) { StatusScreen::loadBitmaps(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 8fa4800d6a..06f64d38cb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -145,10 +145,10 @@ class BedMeshScreen : public BaseScreen, public CachedScreen Date: Thu, 9 Apr 2020 18:09:36 -0500 Subject: [PATCH 0126/1454] =?UTF-8?q?Show=20"Pausing=E2=80=A6"=20during=20?= =?UTF-8?q?pause?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/ultralcd.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 2d5ae84ed3..29430997c2 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -342,6 +342,7 @@ namespace Language_en { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Done"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Back"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceed"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause Print"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Resume Print"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop Print"); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 08597451a0..7aac51ee81 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1454,7 +1454,7 @@ void MarlinUI::update() { void MarlinUI::pause_print() { #if HAS_LCD_MENU - synchronize(GET_TEXT(MSG_PAUSE_PRINT)); + synchronize(GET_TEXT(MSG_PAUSING)); #endif #if ENABLED(HOST_PROMPT_SUPPORT) From 7af0da7f930e8864dd4ec6df05a20727a2a090de Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 10 Apr 2020 00:03:54 +0000 Subject: [PATCH 0127/1454] [cron] Bump distribution date (2020-04-10) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 75b7682497..8fcd4d53e8 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-09" + #define STRING_DISTRIBUTION_DATE "2020-04-10" #endif /** From 48919c54fb4e793b6bb17022f9badbd3530733ae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 9 Apr 2020 20:05:58 -0500 Subject: [PATCH 0128/1454] Add SRAM command injection (#17459) --- Marlin/src/gcode/queue.cpp | 50 +++++++++++++++------- Marlin/src/gcode/queue.h | 32 +++++++++++--- Marlin/src/lcd/language/language_cz.h | 4 +- Marlin/src/lcd/language/language_de.h | 4 +- Marlin/src/lcd/language/language_en.h | 4 +- Marlin/src/lcd/language/language_es.h | 4 +- Marlin/src/lcd/language/language_gl.h | 4 +- Marlin/src/lcd/language/language_it.h | 4 +- Marlin/src/lcd/language/language_pl.h | 4 +- Marlin/src/lcd/language/language_pt_br.h | 4 +- Marlin/src/lcd/language/language_ru.h | 4 +- Marlin/src/lcd/language/language_sk.h | 4 +- Marlin/src/lcd/language/language_tr.h | 4 +- Marlin/src/lcd/language/language_vi.h | 4 +- Marlin/src/lcd/language/language_zh_CN.h | 4 +- Marlin/src/lcd/language/language_zh_TW.h | 4 +- Marlin/src/lcd/menu/menu.cpp | 16 ------- Marlin/src/lcd/menu/menu.h | 5 --- Marlin/src/lcd/menu/menu_advanced.cpp | 8 ++-- Marlin/src/lcd/menu/menu_filament.cpp | 9 ++-- Marlin/src/lcd/menu/menu_ubl.cpp | 53 ++++++++++-------------- 21 files changed, 120 insertions(+), 109 deletions(-) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index abb50b960d..43272e7835 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -86,11 +86,15 @@ static int serial_count[NUM_SERIAL] = { 0 }; bool send_ok[BUFSIZE]; /** - * Next Injected Command pointer. nullptr if no commands are being injected. - * Used by Marlin internally to ensure that commands initiated from within - * are enqueued ahead of any pending serial or sd card commands. + * Next Injected PROGMEM Command pointer. (nullptr == empty) + * Internal commands are enqueued ahead of serial / SD commands. */ -static PGM_P injected_commands_P = nullptr; +PGM_P GCodeQueue::injected_commands_P; // = nullptr + +/** + * Injected SRAM Commands + */ +char GCodeQueue::injected_commands[64]; // = { 0 } GCodeQueue::GCodeQueue() { // Send "ok" after commands by default @@ -101,7 +105,7 @@ GCodeQueue::GCodeQueue() { * Check whether there are any commands yet to be executed */ bool GCodeQueue::has_commands_queued() { - return queue.length || injected_commands_P; + return queue.length || injected_commands_P || injected_commands[0]; } /** @@ -172,11 +176,10 @@ bool GCodeQueue::enqueue_one(const char* cmd) { } /** - * Process the next "immediate" command. - * Return 'true' if any commands were processed, - * or remain to process. + * Process the next "immediate" command from PROGMEM. + * Return 'true' if any commands were processed. */ -bool GCodeQueue::process_injected_command() { +bool GCodeQueue::process_injected_command_P() { if (injected_commands_P == nullptr) return false; char c; @@ -198,12 +201,27 @@ bool GCodeQueue::process_injected_command() { } /** - * Enqueue one or many commands to run from program memory. - * Do not inject a comment or use leading spaces! - * Aborts the current queue, if any. - * Note: process_injected_command() will be called to drain any commands afterwards + * Process the next "immediate" command from SRAM. + * Return 'true' if any commands were processed. */ -void GCodeQueue::inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; } +bool GCodeQueue::process_injected_command() { + if (injected_commands[0] == '\0') return false; + + char c; + size_t i = 0; + while ((c = injected_commands[i]) && c != '\n') i++; + + // Execute a non-blank command + if (i) { + injected_commands[i] = '\0'; + parser.parse(injected_commands); + gcode.process_parsed_command(); + } + + // Copy the next command into place + strcpy(injected_commands, &injected_commands[i + (c != '\0')]); + return true; +} /** * Enqueue and return only when commands are actually enqueued. @@ -575,7 +593,7 @@ void GCodeQueue::get_serial_commands() { /** * Add to the circular command queue the next command from: - * - The command-injection queue (injected_commands_P) + * - The command-injection queues (injected_commands_P, injected_commands) * - The active serial input (usually USB) * - The SD card file being actively printed */ @@ -594,7 +612,7 @@ void GCodeQueue::get_available_commands() { void GCodeQueue::advance() { // Process immediate commands - if (process_injected_command()) return; + if (process_injected_command_P() || process_injected_command()) return; // Return if the G-code buffer is empty if (!length) return; diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 6a87d47ac8..053d143e76 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -66,11 +66,30 @@ public: static void clear(); /** - * Enqueue one or many commands to run from program memory. - * Aborts the current queue, if any. - * Note: process_injected_command() will process them. + * Next Injected Command (PROGMEM) pointer. (nullptr == empty) + * Internal commands are enqueued ahead of serial / SD commands. */ - static void inject_P(PGM_P const pgcode); + static PGM_P injected_commands_P; + + /** + * Injected Commands (SRAM) + */ + static char injected_commands[64]; + + /** + * Enqueue command(s) to run from PROGMEM. Drained by process_injected_command_P(). + * Don't inject comments or use leading spaces! + * Aborts the current PROGMEM queue so only use for one or two commands. + */ + static inline void inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; } + + /** + * Enqueue command(s) to run from SRAM. Drained by process_injected_command(). + * Aborts the current SRAM queue so only use for one or two commands. + */ + static inline void inject(char * const gcode) { + strncpy(injected_commands, gcode, sizeof(injected_commands) - 1); + } /** * Enqueue and return only when commands are actually enqueued @@ -145,7 +164,10 @@ private: #endif ); - // Process the next "immediate" command + // Process the next "immediate" command (PROGMEM) + static bool process_injected_command_P(); + + // Process the next "immediate" command (SRAM) static bool process_injected_command(); /** diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 77e25b7332..f4855f9f88 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -197,8 +197,8 @@ namespace Language_cz { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Paměťový slot"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Načíst síť bodů"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Uložit síť bodů"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Síť %i načtena"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Síť %i uložena"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Síť %i načtena"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Síť %i uložena"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nedostatek místa"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Ch.: Uložit UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Ch.: Obnovit UBL"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index cd201ded34..fbe74a6c67 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -179,8 +179,8 @@ namespace Language_de { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Speicherort"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Bettnetz laden"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Bettnetz speichern"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Netz %i geladen"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Netz %i gespeichert"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Netz %i geladen"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Netz %i gespeichert"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Kein Speicher"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err:UBL speichern"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err:UBL wiederherst."); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 29430997c2..b116faad47 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -190,8 +190,8 @@ namespace Language_en { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memory Slot"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Load Bed Mesh"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Save Bed Mesh"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Mesh %i Loaded"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Mesh %i Saved"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i Loaded"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("No Storage"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err: UBL Save"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err: UBL Restore"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 54e05a1c41..0ee760ed27 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -186,8 +186,8 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Huecos de memoria"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Mallado cama"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Guardar Mallado cama"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Mall. %i Carga."); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Mall. %i Guard."); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mall. %i Carga."); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mall. %i Guard."); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sin guardar"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Error: Guardar UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Error: Restaurar UBL"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index c40c0c1f7d..df95e74e70 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -189,8 +189,8 @@ namespace Language_gl { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Rañura Memoria"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Malla Cama"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Gardar Malla Cama"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Malla %i Cargada"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Malla %i Gardada"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malla %i Gardada"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sen Gardar"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Erro: Gardadado UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Erro: Recuperación UBL"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index c7f0585df5..d503481a5c 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -188,8 +188,8 @@ namespace Language_it { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot di memoria"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Carica Mesh Piatto"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Salva Mesh Piatto"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Mesh %i caricata"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Mesh %i salvata"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i caricata"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i salvata"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nessuna memoria"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err: Salvataggio UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err: Ripristino UBL"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 9fefeb6ee0..78676128cc 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -186,8 +186,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot Pamięci"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Załaduj siatke stołu"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Zapisz siatke stołu"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Siatka %i załadowana"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Siatka %i Zapisana"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Siatka %i załadowana"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Siatka %i Zapisana"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Brak magazynu"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Błąd: Zapis UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Bład: Odczyt UBL"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 9ce6a7042b..8fd771ab05 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -156,8 +156,8 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot de Memória"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ler Malha"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Salvar Malha"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Malha %i carregada"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Malha %i salva"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malha %i carregada"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malha %i salva"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sem armazenamento"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Erro ao salvar UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Erro no restauro UBL"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index a7c971e8c7..8d2a722b19 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -167,8 +167,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Слот памяти"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Загрузить сетку стола"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Сохранить сетку стола"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Сетка %i загружена"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Сетка %i сохранена"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Сетка %i загружена"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Сетка %i сохранена"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Нет хранилища"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Ошибка: Сохран. UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Ошибка: Восстан. UBL"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 4205cd5988..0d1218f103 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -189,8 +189,8 @@ namespace Language_sk { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Pamäťový slot"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Načítať sieť bodov"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Uložiť sieť bodov"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Sieť %i načítaná"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Sieť %i uložená"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Sieť %i načítaná"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Sieť %i uložená"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nedostatok miesta"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Chyba: Ukladanie UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Chyba: Obnovenie UBL"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 515f4d0037..4541fa8363 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -191,8 +191,8 @@ namespace Language_tr { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Bellek Yuvası"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Yatak Mesh Yükle"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Yatak Mesh Kayıt Et"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Mesh %i yüklendi"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Mesh %i kayıtlandı"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i yüklendi"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i kayıtlandı"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Depolama Yok"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Hata: UBL Kayıt"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Hata: UBL Yenileme"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 330db4b690..8d13fdb194 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -159,8 +159,8 @@ namespace Language_vi { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Khe nhớ"); // Memory Slot PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Tải lưới bàn"); // Load Bed Mesh PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Lưu lưới bàn"); // Save Bed Mesh - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 %i lưới được nạp"); // Mesh %i loaded - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 %i lưới đã lưu"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("%i lưới được nạp"); // Mesh %i loaded + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("%i lưới đã lưu"); PROGMEM Language_Str MSG_NO_STORAGE = _UxGT("Không lưu trữ"); // No Storage PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Điều sai: Lưu UBL"); // Err: UBL Save PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Điều Sai: Khôi Phục UBL"); // Err: UBL Restore diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 742375c7d1..0207c47baa 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -136,8 +136,8 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("存储槽"); // "Memory Slot" PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("装载热床网格"); // "Load Bed Mesh" PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("保存热床网格"); // "Save Bed Mesh" - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 网格 %i 已装载"); // "Mesh %i loaded" - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 网格 %i 已保存"); // "Mesh %i saved" + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("网格 %i 已装载"); // "Mesh %i loaded" + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("网格 %i 已保存"); // "Mesh %i saved" PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("没有存储"); // "No storage" PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("错误: UBL保存"); // "Err: UBL Save" PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("错误: UBL还原"); // "Err: UBL Restore" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 053a90d586..f9eeb0e649 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -184,8 +184,8 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("存儲槽"); // "Memory Slot" PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("裝載熱床網格"); // "Load Bed Mesh" PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("保存熱床網格"); // "Save Bed Mesh" - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 網格 %i 已裝載"); // "Mesh %i loaded" - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 網格 %i 已保存"); // "Mesh %i saved" + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("網格 %i 已裝載"); // "Mesh %i loaded" + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("網格 %i 已保存"); // "Mesh %i saved" PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("沒有存儲"); // "No storage" PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("錯誤: UBL保存"); // "Err: UBL Save" PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("錯誤: UBL還原"); // "Err: UBL Restore" diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 501120252a..192125c7d0 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -438,22 +438,6 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #endif // BABYSTEP_ZPROBE_OFFSET -#if ANY(AUTO_BED_LEVELING_UBL, PID_AUTOTUNE_MENU, ADVANCED_PAUSE_FEATURE) - - void lcd_enqueue_one_now(const char * const cmd) { - no_reentry = true; - queue.enqueue_one_now(cmd); - no_reentry = false; - } - - void lcd_enqueue_one_now_P(PGM_P const cmd) { - no_reentry = true; - queue.enqueue_now_P(cmd); - no_reentry = false; - } - -#endif - #if ENABLED(EEPROM_SETTINGS) void lcd_store_settings() { const bool saved = settings.save(); diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index e9ec3b2496..5d4b655167 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -547,11 +547,6 @@ void _lcd_draw_homing(); void line_to_z(const float &z); #endif -#if ANY(AUTO_BED_LEVELING_UBL, PID_AUTOTUNE_MENU, ADVANCED_PAUSE_FEATURE) - void lcd_enqueue_one_now(const char * const cmd); - void lcd_enqueue_one_now_P(PGM_P const cmd); -#endif - #if HAS_GRAPHICAL_LCD && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void _lcd_zoffset_overlay_gfx(const float zvalue); #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index f2327b75e5..ac755af7c4 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -178,18 +178,18 @@ void menu_cancelobject(); int16_t autotune_temp_bed = 70; #endif + #include "../../gcode/queue.h" + void _lcd_autotune(const int16_t e) { char cmd[30]; sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), e, #if HAS_PID_FOR_BOTH e < 0 ? autotune_temp_bed : autotune_temp[e] - #elif ENABLED(PIDTEMPBED) - autotune_temp_bed #else - autotune_temp[e] + TERN(PIDTEMPBED, autotune_temp_bed, autotune_temp[e]) #endif ); - lcd_enqueue_one_now(cmd); + queue.inject(cmd); } #endif // PID_AUTOTUNE_MENU diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 0c8f1f61c8..608936aadb 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -31,6 +31,7 @@ #include "menu.h" #include "../../module/temperature.h" #include "../../feature/pause.h" +#include "../../gcode/queue.h" #if HAS_FILAMENT_SENSOR #include "../../feature/runout.h" #endif @@ -60,7 +61,7 @@ static void _change_filament_temp(const uint16_t temperature) { char cmd[11]; sprintf_P(cmd, _change_filament_temp_command(), _change_filament_temp_extruder); thermalManager.setTargetHotend(temperature, _change_filament_temp_extruder); - lcd_enqueue_one_now(cmd); + queue.inject(cmd); } // @@ -121,7 +122,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { ACTION_ITEM_N_P(s, msg, []{ char cmd[13]; sprintf_P(cmd, PSTR("M600 B0 T%i"), int(MenuItemBase::itemIndex)); - lcd_enqueue_one_now(cmd); + queue.inject(cmd); }); } } @@ -145,7 +146,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { ACTION_ITEM_N_P(s, msg_load, []{ char cmd[12]; sprintf_P(cmd, PSTR("M701 T%i"), int(MenuItemBase::itemIndex)); - lcd_enqueue_one_now(cmd); + queue.inject(cmd); }); } } @@ -181,7 +182,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { ACTION_ITEM_N_P(s, msg_unload, []{ char cmd[12]; sprintf_P(cmd, PSTR("M702 T%i"), int(MenuItemBase::itemIndex)); - lcd_enqueue_one_now(cmd); + queue.inject(cmd); }); } } diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 8488c11c7d..10c85332ab 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -29,6 +29,8 @@ #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL) #include "menu.h" +#include "../../gcode/gcode.h" +#include "../../gcode/queue.h" #include "../../module/planner.h" #include "../../module/configuration_store.h" #include "../../feature/bedlevel/bedlevel.h" @@ -106,15 +108,13 @@ void lcd_z_offset_edit_setup(const float &initial) { * UBL Build Custom Mesh Command */ void _lcd_ubl_build_custom_mesh() { - char ubl_lcd_gcode[20]; - queue.inject_P(G28_STR); + char ubl_lcd_gcode[64]; #if HAS_HEATED_BED - sprintf_P(ubl_lcd_gcode, PSTR("M190 S%i"), custom_bed_temp); - lcd_enqueue_one_now(ubl_lcd_gcode); + sprintf_P(ubl_lcd_gcode, PSTR("G28\nM190 S%i\nM109 S%i\nG29 P1"), custom_bed_temp, custom_hotend_temp); + #else + sprintf_P(ubl_lcd_gcode, PSTR("G28\nM109 S%i\nG29 P1"), custom_hotend_temp); #endif - sprintf_P(ubl_lcd_gcode, PSTR("M109 S%i"), custom_hotend_temp); - lcd_enqueue_one_now(ubl_lcd_gcode); - queue.inject_P(PSTR("G29 P1")); + queue.inject(ubl_lcd_gcode); } /** @@ -144,7 +144,7 @@ void _lcd_ubl_adjust_height_cmd() { const int ind = ubl_height_amount > 0 ? 9 : 10; strcpy_P(ubl_lcd_gcode, PSTR("G29 P6 C -")); sprintf_P(&ubl_lcd_gcode[ind], PSTR(".%i"), ABS(ubl_height_amount)); - lcd_enqueue_one_now(ubl_lcd_gcode); + queue.inject(ubl_lcd_gcode); } /** @@ -187,16 +187,9 @@ void _lcd_ubl_edit_mesh() { */ void _lcd_ubl_validate_custom_mesh() { char ubl_lcd_gcode[24]; - const int temp = - #if HAS_HEATED_BED - custom_bed_temp - #else - 0 - #endif - ; - sprintf_P(ubl_lcd_gcode, PSTR("G26 C B%i H%i P"), temp, custom_hotend_temp); - lcd_enqueue_one_now_P(G28_STR); - lcd_enqueue_one_now(ubl_lcd_gcode); + const int temp = TERN(HAS_HEATED_BED, custom_bed_temp, 0); + sprintf_P(ubl_lcd_gcode, PSTR("G28\nG26 C B%i H%i P"), temp, custom_hotend_temp); + queue.inject(ubl_lcd_gcode); } /** @@ -237,7 +230,7 @@ void _lcd_ubl_grid_level() { ACTION_ITEM(MSG_UBL_MESH_LEVEL, []{ char ubl_lcd_gcode[12]; sprintf_P(ubl_lcd_gcode, PSTR("G29 J%i"), side_points); - lcd_enqueue_one_now(ubl_lcd_gcode); + queue.inject(ubl_lcd_gcode); }); END_MENU(); } @@ -265,7 +258,7 @@ void _lcd_ubl_mesh_leveling() { void _lcd_ubl_fillin_amount_cmd() { char ubl_lcd_gcode[18]; sprintf_P(ubl_lcd_gcode, PSTR("G29 P3 R C.%i"), ubl_fillin_amount); - lcd_enqueue_one_now(ubl_lcd_gcode); + gcode.process_subcommands_now(ubl_lcd_gcode); } /** @@ -355,22 +348,20 @@ void _lcd_ubl_build_mesh() { * UBL Load Mesh Command */ void _lcd_ubl_load_mesh_cmd() { - char ubl_lcd_gcode[25]; - sprintf_P(ubl_lcd_gcode, PSTR("G29 L%i"), ubl_storage_slot); - lcd_enqueue_one_now(ubl_lcd_gcode); - sprintf_P(ubl_lcd_gcode, GET_TEXT(MSG_MESH_LOADED), ubl_storage_slot); - lcd_enqueue_one_now(ubl_lcd_gcode); + char ubl_lcd_gcode[40]; + sprintf_P(ubl_lcd_gcode, PSTR("G29 L%i\nM117 "), ubl_storage_slot); + sprintf_P(&ubl_lcd_gcode[strlen(ubl_lcd_gcode)], GET_TEXT(MSG_MESH_LOADED), ubl_storage_slot); + gcode.process_subcommands_now(ubl_lcd_gcode); } /** * UBL Save Mesh Command */ void _lcd_ubl_save_mesh_cmd() { - char ubl_lcd_gcode[25]; - sprintf_P(ubl_lcd_gcode, PSTR("G29 S%i"), ubl_storage_slot); - lcd_enqueue_one_now(ubl_lcd_gcode); - sprintf_P(ubl_lcd_gcode, GET_TEXT(MSG_MESH_SAVED), ubl_storage_slot); - lcd_enqueue_one_now(ubl_lcd_gcode); + char ubl_lcd_gcode[40]; + sprintf_P(ubl_lcd_gcode, PSTR("G29 S%i\nM117 "), ubl_storage_slot); + sprintf_P(&ubl_lcd_gcode[strlen(ubl_lcd_gcode)], GET_TEXT(MSG_MESH_SAVED), ubl_storage_slot); + gcode.process_subcommands_now(ubl_lcd_gcode); } /** @@ -418,7 +409,7 @@ void _lcd_ubl_map_lcd_edit_cmd() { dtostrf(ubl.mesh_index_to_xpos(x_plot), 0, 2, str); dtostrf(ubl.mesh_index_to_ypos(y_plot), 0, 2, str2); snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), PSTR("G29 P4 X%s Y%s R%i"), str, str2, int(n_edit_pts)); - lcd_enqueue_one_now(ubl_lcd_gcode); + queue.inject(ubl_lcd_gcode); } /** From 8647d6b8d83fb27de4f4f70b9d47a495e27a4b41 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 11 Apr 2020 00:03:20 +0000 Subject: [PATCH 0129/1454] [cron] Bump distribution date (2020-04-11) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8fcd4d53e8..034754af41 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-10" + #define STRING_DISTRIBUTION_DATE "2020-04-11" #endif /** From a65198882f04622546ebf73903f7618f1eccd92a Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sat, 11 Apr 2020 10:25:19 -0500 Subject: [PATCH 0130/1454] Make declaration of PID_debug_flag match M303.cpp --- Marlin/src/module/temperature.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f9f311635e..899cd2dd76 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -823,7 +823,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #if HOTENDS #if ENABLED(PID_DEBUG) - extern bool PID_Debug_Flag; + extern bool PID_debug_flag; #endif float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { @@ -906,7 +906,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #endif // PID_OPENLOOP #if ENABLED(PID_DEBUG) - if (ee == active_extruder && PID_Debug_Flag) { + if (ee == active_extruder && PID_debug_flag) { SERIAL_ECHO_START(); SERIAL_ECHOPAIR(STR_PID_DEBUG, ee, STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, STR_PID_DEBUG_OUTPUT, pid_output); #if DISABLED(PID_OPENLOOP) From 07c9dc414219af67ebf016f1e2f1b4e683c4a3b1 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sat, 11 Apr 2020 11:03:04 -0500 Subject: [PATCH 0131/1454] Make pid_debug_flag match declaration in M303.cpp Get it right this time! --- Marlin/src/module/temperature.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 899cd2dd76..650cda51f3 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -823,7 +823,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #if HOTENDS #if ENABLED(PID_DEBUG) - extern bool PID_debug_flag; + extern bool pid_debug_flag; #endif float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { @@ -906,7 +906,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #endif // PID_OPENLOOP #if ENABLED(PID_DEBUG) - if (ee == active_extruder && PID_debug_flag) { + if (ee == active_extruder && pid_debug_flag) { SERIAL_ECHO_START(); SERIAL_ECHOPAIR(STR_PID_DEBUG, ee, STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, STR_PID_DEBUG_OUTPUT, pid_output); #if DISABLED(PID_OPENLOOP) From dfb5968bfe56b0e4450ca3b224e601c818857736 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 12 Apr 2020 00:03:21 +0000 Subject: [PATCH 0132/1454] [cron] Bump distribution date (2020-04-12) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 034754af41..6ffec1d458 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-11" + #define STRING_DISTRIBUTION_DATE "2020-04-12" #endif /** From e4903396d4ac2fa9b89dd535dae9c3e8a68b3526 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Apr 2020 20:36:17 -0500 Subject: [PATCH 0133/1454] Fix up pausing / parking display (#17460) --- Marlin/src/feature/pause.h | 2 +- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- Marlin/src/lcd/language/language_cz.h | 4 +-- Marlin/src/lcd/language/language_de.h | 4 +-- Marlin/src/lcd/language/language_en.h | 4 +-- Marlin/src/lcd/language/language_es.h | 4 +-- Marlin/src/lcd/language/language_fr.h | 2 +- Marlin/src/lcd/language/language_gl.h | 4 +-- Marlin/src/lcd/language/language_it.h | 2 +- Marlin/src/lcd/language/language_pl.h | 4 +-- Marlin/src/lcd/language/language_sk.h | 4 +-- Marlin/src/lcd/language/language_tr.h | 4 +-- Marlin/src/lcd/language/language_zh_TW.h | 4 +-- Marlin/src/lcd/menu/menu.cpp | 34 +++++++----------------- Marlin/src/lcd/menu/menu_filament.cpp | 4 +-- Marlin/src/lcd/menu/menu_ubl.cpp | 12 ++++----- Marlin/src/lcd/ultralcd.cpp | 7 +++-- Marlin/src/lcd/ultralcd.h | 2 -- 18 files changed, 43 insertions(+), 60 deletions(-) diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index f1c8eed4d3..a4d5a9ae83 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -45,7 +45,7 @@ enum PauseMode : char { }; enum PauseMessage : char { - PAUSE_MESSAGE_PAUSING, + PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_WAITING, PAUSE_MESSAGE_UNLOAD, diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 206815a200..79ed6e785a 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -82,7 +82,7 @@ void GcodeSuite::M125() { #endif #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_PAUSING, PAUSE_MODE_PAUSE_PRINT); + lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); const bool show_lcd = parser.seenval('P'); #else constexpr bool show_lcd = false; diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index f4855f9f88..caa458402a 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -563,7 +563,7 @@ namespace Language_cz { #if LCD_HEIGHT >= 4 // Up to 3 lines allowed PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stikněte tlačítko", "pro obnovení tisku")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkování...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkování...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čekejte prosím", "na zahájení", "výměny filamentu")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Vložte filament", "a stiskněte", "tlačítko...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klikněte pro", "nahřátí trysky")); @@ -576,7 +576,7 @@ namespace Language_cz { #else // LCD_HEIGHT < 4 // Up to 2 lines allowed PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stikněte tlač.", "pro obnovení")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkování...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkování...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Čekejte...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Vložte, klikněte")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klikněte pro", "nahřátí")); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index fbe74a6c67..aa3f0a5f01 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -523,7 +523,7 @@ namespace Language_de { // ...oder 2 Zeilen auf einem 3-Zeilen-Display. #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Knopf drücken um", "Druck fortzusetzen")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_2_LINE("Druck ist", "pausiert...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_2_LINE("Druck ist", "pausiert...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Warte auf den", "Start des", "Filamentwechsels...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Filament einlegen", "und Knopf drücken", "um fortzusetzen")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Knopf drücken um", "Düse aufzuheizen")); @@ -535,7 +535,7 @@ namespace Language_de { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Warte auf", "Fortsetzen des", "Drucks...")); #else // LCD_HEIGHT < 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Klick zum Fortsetzen")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Pausiert...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Pausiert...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Bitte warten...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Laden und Klick")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Klick zum Heizen")); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index b116faad47..f9a9671bb2 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -565,7 +565,7 @@ namespace Language_en { // #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Press Button", "to resume print")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parking...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Wait for", "filament change", "to start")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Insert filament", "and press button", "to continue")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Press button", "to heat nozzle")); @@ -577,7 +577,7 @@ namespace Language_en { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wait for print", "to resume...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Click to continue")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parking...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Please wait...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insert and Click")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Click to heat")); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 0ee760ed27..f921ce5111 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -555,7 +555,7 @@ namespace Language_es { #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Pulsar el botón para", "reanudar impresión")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Aparcando...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Aparcando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperando para", "iniciar el cambio", "de filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserte el filamento", "y pulse el botón", "para continuar...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Pulse el botón para", "calentar la boquilla")); @@ -567,7 +567,7 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impresora", "para reanudar...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Pulse para continuar")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Aparcando...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Aparcando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Por Favor espere...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Inserte y Pulse")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Pulse para Calentar")); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index e691d26ab4..6196f40c64 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -508,7 +508,7 @@ namespace Language_fr { #if LCD_HEIGHT >= 4 // Up to 3 lines allowed PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Presser bouton", "pour reprendre")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parking...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Attente filament", "pour démarrer")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Insérer filament", "et app. bouton", "pour continuer...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Presser le bouton", "pour chauffer...")); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index df95e74e70..d9d07f8ec2 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -558,7 +558,7 @@ namespace Language_gl { #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Preme o botón para", "continuar impresión")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Estacionando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "comezar cambio", "de filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Introduza o", "filamento e", "faga click")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Prema o botón para", "quentar o bico")); @@ -570,7 +570,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde a que", "se retome", "a impresión")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premer para continuar")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Estacionando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Agarde...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Introduza e click")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Prema para quentar")); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index d503481a5c..84438f2847 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -558,7 +558,7 @@ namespace Language_it { // ...o fino a 2 linee su un display a 3 righe. #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Premi per", "riprendere", "la stampa")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parcheggiando...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcheggiando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Attendere avvio", "del cambio", "di filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserisci il", "filamento e premi", "per continuare")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Premi per", "riscaldare ugello")); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 78676128cc..469bed05b1 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -529,7 +529,7 @@ namespace Language_pl { // #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nacisnik przycisk", "by wznowić drukowanie")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkowanie...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkowanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Czekam na", "zmianę filamentu", "by wystartować")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Włóż filament", "i naciśnij przycisk", "by kontynuować")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Naciśnij przycisk", "by nagrzać dyszę")); @@ -541,7 +541,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Czekam na", "wznowienie wydruku...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Kliknij by kontynuować")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkowanie...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkowanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Proszę czekać...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Włóż i kliknij")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknij by nagrzać")); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 0d1218f103..6f7707421e 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -545,7 +545,7 @@ namespace Language_sk { // #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stlačte tlačidlo", "pre obnovu tlače")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkovanie...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkovanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čakajte prosím", "na spustenie", "výmeny filamentu")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Vložte filament", "a stlačte tlačidlo", "pre pokračovanie")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Stlačte tlačidlo", "pre ohrev trysky")); @@ -557,7 +557,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Čakajte prosím na", "obnovenie tlače...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Kliknite pre pokr.")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkovanie...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkovanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Čakajte prosím...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Vložte a kliknite")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknite pre ohrev")); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 4541fa8363..7db3592902 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -556,7 +556,7 @@ namespace Language_tr { #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Baskıya devam etmek", "için Butona bas")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Park Ediliyor...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Park Ediliyor...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Filaman değişimi", "için başlama", "bekleniyor")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Filamanı yükle", "ve devam için", "tuşa bas...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nozulü Isıtmak için", "Butona Bas.")); @@ -568,7 +568,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Baskının devam ", "etmesi için bekle")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Sürdürmek İçin Tıkla")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Park Ediliyor...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Park Ediliyor...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Lütfen bekleyiniz...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Yükle ve bas")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Isıtmak için Tıkla")); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index f9eeb0e649..a0812a89f3 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -552,7 +552,7 @@ namespace Language_zh_TW { // #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("按下按鈕", "恢復列印")); //"Press Button to resume print" - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("等待開始", "絲料", "變更")); //"Wait for start of the filament change" PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("等待", "卸下絲料")); //"Wait for filament unload" PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("插入絲料", "並按鍵", "繼續 ...")); //"Insert filament and press button to continue..." @@ -564,7 +564,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("等待列印", "恢復")); //"Wait for print to resume" #else // LCD_HEIGHT < 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下繼續..")); //"Click to continue" - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("請等待 ...")); //"Please wait..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入並點擊")); //"Insert and Click" PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("按下加熱..")); //"Click to heat" diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 192125c7d0..3dd9932044 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -76,9 +76,6 @@ int32_t MenuEditItemBase::minEditValue, screenFunc_t MenuEditItemBase::callbackFunc; bool MenuEditItemBase::liveEdit; -// Prevent recursion into screen handlers -bool no_reentry = false; - //////////////////////////////////////////// //////// Menu Navigation & History ///////// //////////////////////////////////////////// @@ -314,29 +311,18 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co //////////////////////////////////////////// // -// Display the synchronize screen until moves are -// finished, and don't return to the caller until -// done. ** This blocks the command queue! ** +// Display a "synchronize" screen with a custom message until +// all moves are finished. Go back to calling screen when done. // -static PGM_P sync_message; - -void MarlinUI::_synchronize() { - if (should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, sync_message); - if (no_reentry) return; - // Make this the current handler till all moves are done - const screenFunc_t old_screen = currentScreen; - goto_screen(_synchronize); - no_reentry = true; - planner.synchronize(); // idle() is called until moves complete - no_reentry = false; - goto_screen(old_screen); -} - -// Display the synchronize screen with a custom message -// ** This blocks the command queue! ** void MarlinUI::synchronize(PGM_P const msg/*=nullptr*/) { - sync_message = msg ?: GET_TEXT(MSG_MOVING); - _synchronize(); + static PGM_P sync_message = msg ?: GET_TEXT(MSG_MOVING); + save_previous_screen(); + goto_screen([]{ + if (should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, sync_message); + }); + defer_status_screen(); + planner.synchronize(); // idle() is called until moves complete + goto_previous_screen_no_defer(); } /** diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 608936aadb..5b6cbed6af 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -262,7 +262,7 @@ void _lcd_pause_message(PGM_P const msg) { END_SCREEN(); } -void lcd_pause_pausing_message() { _lcd_pause_message(GET_TEXT(MSG_PAUSE_PRINT_INIT)); } +void lcd_pause_parking_message() { _lcd_pause_message(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); } void lcd_pause_changing_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); } void lcd_pause_unload_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); } void lcd_pause_heating_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); } @@ -282,7 +282,7 @@ void lcd_pause_purge_message() { FORCE_INLINE screenFunc_t ap_message_screen(const PauseMessage message) { switch (message) { - case PAUSE_MESSAGE_PAUSING: return lcd_pause_pausing_message; + case PAUSE_MESSAGE_PARKING: return lcd_pause_parking_message; case PAUSE_MESSAGE_CHANGING: return lcd_pause_changing_message; case PAUSE_MESSAGE_UNLOAD: return lcd_pause_unload_message; case PAUSE_MESSAGE_WAITING: return lcd_pause_waiting_message; diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 10c85332ab..4d7edbdfd1 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -51,7 +51,7 @@ float mesh_edit_value, mesh_edit_accumulator; // We round mesh_edit_value to 2.5 // separate value that doesn't lose precision. static int16_t ubl_encoderPosition = 0; -static void _lcd_mesh_fine_tune(PGM_P msg) { +static void _lcd_mesh_fine_tune(PGM_P const msg) { ui.defer_status_screen(); if (ubl.encoder_diff) { ubl_encoderPosition = (ubl.encoder_diff > 0) ? 1 : -1; @@ -74,12 +74,13 @@ static void _lcd_mesh_fine_tune(PGM_P msg) { } } -void _lcd_mesh_edit_NOP() { +void lcd_limbo() { + ui.currentScreen = []{}; ui.defer_status_screen(); } float lcd_mesh_edit() { - ui.goto_screen(_lcd_mesh_edit_NOP); + lcd_limbo(); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); _lcd_mesh_fine_tune(GET_TEXT(MSG_MESH_EDITOR)); return mesh_edit_value; @@ -87,7 +88,7 @@ float lcd_mesh_edit() { void lcd_mesh_edit_setup(const float &initial) { mesh_edit_value = mesh_edit_accumulator = initial; - ui.goto_screen(_lcd_mesh_edit_NOP); + lcd_limbo(); } void _lcd_z_offset_edit() { @@ -437,10 +438,9 @@ void ubl_map_move_to_xy() { void set_current_from_steppers_for_axis(const AxisEnum axis); void sync_plan_position(); -void _lcd_do_nothing() {} void _lcd_hard_stop() { const screenFunc_t old_screen = ui.currentScreen; - ui.currentScreen = _lcd_do_nothing; + lcd_limbo(); planner.quick_stop(); ui.currentScreen = old_screen; set_current_from_steppers_for_axis(ALL_AXES); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 7aac51ee81..980c561a7e 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -638,8 +638,6 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #if HAS_LCD_MENU - extern bool no_reentry; // Flag to prevent recursion into menu handlers - int8_t manual_move_axis = (int8_t)NO_AXIS; millis_t manual_move_start_time = 0; @@ -767,7 +765,7 @@ void MarlinUI::update() { auto do_click = [&]{ wait_for_unclick = true; // - Set debounce flag to ignore continous clicks - lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click + lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click wait_for_user = false; // - Any click clears wait for user quick_feedback(); // - Always make a click sound }; @@ -1455,6 +1453,7 @@ void MarlinUI::update() { void MarlinUI::pause_print() { #if HAS_LCD_MENU synchronize(GET_TEXT(MSG_PAUSING)); + defer_status_screen(); #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -1465,7 +1464,7 @@ void MarlinUI::update() { #if ENABLED(PARK_HEAD_ON_PAUSE) #if HAS_SPI_LCD - lcd_pause_show_message(PAUSE_MESSAGE_PAUSING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress + lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress #endif queue.inject_P(PSTR("M25 P\nM24")); #elif ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 0be82ff1f6..0c7c03372f 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -624,8 +624,6 @@ public: private: - static void _synchronize(); - #if HAS_DISPLAY static void finish_status(const bool persist); #endif From a97ae51cc7d3fa4b8fa1180d71023964e495b304 Mon Sep 17 00:00:00 2001 From: Ryan Date: Sat, 11 Apr 2020 18:39:02 -0700 Subject: [PATCH 0134/1454] Archim: PIO upload on Windows, Arduino IDE LCD (#17405) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/DUE/upload_extra_script.py | 18 ++++++++++++++++++ Marlin/src/HAL/DUE/usb/conf_usb.h | 4 ---- platformio.ini | 2 ++ 3 files changed, 20 insertions(+), 4 deletions(-) create mode 100644 Marlin/src/HAL/DUE/upload_extra_script.py diff --git a/Marlin/src/HAL/DUE/upload_extra_script.py b/Marlin/src/HAL/DUE/upload_extra_script.py new file mode 100644 index 0000000000..06c2b914f5 --- /dev/null +++ b/Marlin/src/HAL/DUE/upload_extra_script.py @@ -0,0 +1,18 @@ +# +# Set upload_command +# +# Windows: bossac.exe +# Other: leave unchanged +# + +import platform +current_OS = platform.system() + +if current_OS == 'Windows': + + Import("env") + + # Use bossac.exe on Windows + env.Replace( + UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot" + ) diff --git a/Marlin/src/HAL/DUE/usb/conf_usb.h b/Marlin/src/HAL/DUE/usb/conf_usb.h index 8d5924d375..7beb9b0bba 100644 --- a/Marlin/src/HAL/DUE/usb/conf_usb.h +++ b/Marlin/src/HAL/DUE/usb/conf_usb.h @@ -78,10 +78,6 @@ //! To define a Full speed device //#define USB_DEVICE_FULL_SPEED -#if MB(ARCHIM1) - #define USB_DEVICE_FULL_SPEED -#endif - //! To authorize the High speed #ifndef USB_DEVICE_FULL_SPEED #if (UC3A3||UC3A4) diff --git a/platformio.ini b/platformio.ini index d072ae4cc9..38e3065f20 100644 --- a/platformio.ini +++ b/platformio.ini @@ -214,6 +214,7 @@ board = due src_filter = ${common.default_src_filter} + build_flags = ${common.build_flags} -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON +extra_scripts = Marlin/src/HAL/DUE/upload_extra_script.py [env:DUE_archim_debug] # Used when WATCHDOG_RESET_MANUAL is enabled @@ -223,6 +224,7 @@ src_filter = ${common.default_src_filter} + build_flags = ${common.build_flags} -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON -funwind-tables -mpoke-function-name +extra_scripts = Marlin/src/HAL/DUE/upload_extra_script.py # # NXP LPC176x ARM Cortex-M3 From 7aed32df00ae33b6ab2815006ad4c422a9231b69 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Apr 2020 21:27:49 -0500 Subject: [PATCH 0135/1454] Fix SD_FINISHED_RELEASECOMMAND bug Fixes #17401 bug that was introduced in 8f26c3a --- Marlin/Configuration_adv.h | 4 ++-- Marlin/src/gcode/sd/M1001.cpp | 14 +++++++------- Marlin/src/inc/Conditionals_adv.h | 9 +++++++++ Marlin/src/module/planner.cpp | 4 ++-- Marlin/src/module/planner.h | 7 +------ Marlin/src/module/probe.h | 1 - 6 files changed, 21 insertions(+), 18 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d06fe732a4..82cf3e1949 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1035,8 +1035,8 @@ // Enable this option and set to HIGH if your SD cards are incorrectly detected. //#define SD_DETECT_STATE HIGH - #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished - #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the Z enabled so your bed stays in place. + #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished + #define SD_FINISHED_RELEASECOMMAND "M84" // Use "M84XYE" to keep Z enabled so your bed stays in place // Reverse SD sort to show "more recent" files first, according to the card's FAT. // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended. diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 4261b57f97..8f8d4cf56a 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -27,6 +27,10 @@ #include "../gcode.h" #include "../../module/printcounter.h" +#ifdef SD_FINISHED_RELEASECOMMAND + #include "../queue.h" +#endif + #if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) #include "../../lcd/ultralcd.h" #endif @@ -47,10 +51,6 @@ #include "../../feature/host_actions.h" #endif -#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) - #include "../../module/planner.h" -#endif - #ifndef PE_LEDS_COMPLETED_TIME #define PE_LEDS_COMPLETED_TIME (30*60) #endif @@ -95,9 +95,9 @@ void GcodeSuite::M1001() { } #endif - // Wait for the queue to empty (and "clean"), inject SD_FINISHED_RELEASECOMMAND - #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) - planner.finish_and_disable(); + // Inject SD_FINISHED_RELEASECOMMAND, if any + #ifdef SD_FINISHED_RELEASECOMMAND + queue.inject_P(PSTR(SD_FINISHED_RELEASECOMMAND)); #endif // Re-select the last printed file in the UI diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index cda744d81b..65dac5a004 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -68,6 +68,15 @@ #define HAS_FILAMENT_SENSOR 1 #endif +// Let SD_FINISHED_RELEASECOMMAND stand in for SD_FINISHED_STEPPERRELEASE +#if ENABLED(SD_FINISHED_STEPPERRELEASE) + #ifndef SD_FINISHED_RELEASECOMMAND + #define SD_FINISHED_RELEASECOMMAND "M84" // planner.finish_and_disable() + #endif +#else + #undef SD_FINISHED_RELEASECOMMAND +#endif + #if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) #define HAS_PRINT_PROGRESS 1 #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 4ad7a79431..f6be8df9c9 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1601,8 +1601,8 @@ void Planner::quick_stop() { clear_block_buffer_runtime(); #endif - // Make sure to drop any attempt of queuing moves for at least 1 second - cleaning_buffer_counter = 1000; + // Make sure to drop any attempt of queuing moves for 1 second + cleaning_buffer_counter = TEMP_TIMER_FREQUENCY; // Reenable Stepper ISR if (was_enabled) stepper.wake_up(); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index a42c84c1fa..97e907e26b 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -807,12 +807,7 @@ class Planner { // Periodic tick to handle cleaning timeouts // Called from the Temperature ISR at ~1kHz static void tick() { - if (cleaning_buffer_counter) { - --cleaning_buffer_counter; - #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) - if (!cleaning_buffer_counter) queue.inject_P(PSTR(SD_FINISHED_RELEASECOMMAND)); - #endif - } + if (cleaning_buffer_counter) --cleaning_buffer_counter; } /** diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 083867ab48..7b920ab82c 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -47,7 +47,6 @@ public: static bool set_deployed(const bool deploy); - #if IS_KINEMATIC #if HAS_PROBE_XY_OFFSET From 2493cf0364edcd0c28578bb5044c50cd8e775ca1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Apr 2020 01:22:01 -0500 Subject: [PATCH 0136/1454] Fix M1001 with HAS_LEDS_OFF_FLAG --- Marlin/src/gcode/sd/M1001.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 8f8d4cf56a..26c51550ca 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -31,6 +31,10 @@ #include "../queue.h" #endif +#if HAS_LEDS_OFF_FLAG + #include "../../MarlinCore.h" +#endif + #if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) #include "../../lcd/ultralcd.h" #endif From 333092c48836513525ebcc2b763dc8642ab0c401 Mon Sep 17 00:00:00 2001 From: dandantsui <62964600+dandantsui@users.noreply.github.com> Date: Sat, 11 Apr 2020 23:23:08 -0700 Subject: [PATCH 0137/1454] Fix MKS Robin infinite boot (#17497) --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index a8c6d30eb4..7830f14f98 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -40,6 +40,11 @@ // #define DISABLE_JTAG +// +// Enable SD EEPROM to prevent infinite boot loop +// +#define SDCARD_EEPROM_EMULATION + // // Servos // @@ -178,10 +183,10 @@ //#define E4_HARDWARE_SERIAL Serial1 // Unused servo pins may be repurposed with SoftwareSerialM - //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN - //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN - //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN - //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN + //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN -- XS2 - 6 + //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN -- XS2 - 5 + //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN -- XS1 - 6 + //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN -- XS1 - 5 //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN From 37752bd8bb3be8c903ad0fa7b143f4285d5e0a47 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Sun, 12 Apr 2020 08:35:30 +0200 Subject: [PATCH 0138/1454] Update Spanish language (#17465) --- Marlin/src/lcd/language/language_es.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index f921ce5111..0952dde202 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -186,8 +186,8 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Huecos de memoria"); PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Mallado cama"); PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Guardar Mallado cama"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mall. %i Carga."); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mall. %i Guard."); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malla %i Guardada"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sin guardar"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Error: Guardar UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Error: Restaurar UBL"); From 4cdd51cd3a5b57862bfe4758fd8812d1e2fcad94 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 9 Apr 2020 20:58:21 -0500 Subject: [PATCH 0139/1454] Apply TERN to status screen --- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 39 ++++------------------ 1 file changed, 7 insertions(+), 32 deletions(-) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index b4bba3782c..f2703ead7a 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -305,12 +305,7 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons // Homed and known, display constantly. // FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { - const AxisEnum a = ( - #if ENABLED(LCD_SHOW_E_TOTAL) - axis == E_AXIS ? X_AXIS : - #endif - axis - ); + const AxisEnum a = TERN(LCD_SHOW_E_TOTAL, axis == E_AXIS ? X_AXIS : axis, axis); const uint8_t offs = (XYZ_SPACING) * a; lcd_put_wchar(X_LABEL_POS + offs, XYZ_BASELINE, axis_codes[axis]); lcd_moveto(X_VALUE_POS + offs, XYZ_BASELINE); @@ -332,11 +327,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const void MarlinUI::draw_status_screen() { - static char xstring[5 - #if ENABLED(LCD_SHOW_E_TOTAL) - + 7 - #endif - ], ystring[5], zstring[8]; + static char xstring[TERN(LCD_SHOW_E_TOTAL, 12, 5)], ystring[5], zstring[8]; #if ENABLED(FILAMENT_LCD_DISPLAY) static char wstring[5], mstring[4]; #endif @@ -365,11 +356,7 @@ void MarlinUI::draw_status_screen() { #endif #endif - const bool showxy = (true - #if ENABLED(LCD_SHOW_E_TOTAL) - && !printingIsActive() - #endif - ); + const bool showxy = TERN1(LCD_SHOW_E_TOTAL, !printingIsActive()); // At the first page, generate new display values if (first_page) { @@ -411,13 +398,7 @@ void MarlinUI::draw_status_screen() { // Progress / elapsed / estimation updates and string formatting to avoid float math on each LCD draw #if HAS_PRINT_PROGRESS - const progress_t progress = - #if HAS_PRINT_PROGRESS_PERMYRIAD - get_progress_permyriad() - #else - get_progress_percent() - #endif - ; + const progress_t progress = TERN(HAS_PRINT_PROGRESS_PERMYRIAD, get_progress_permyriad, get_progress_percent)(); duration_t elapsed = print_job_timer.duration(); const uint8_t p = progress & 0xFF, ev = elapsed.value & 0xFF; if (p != lastProgress) { @@ -433,15 +414,9 @@ void MarlinUI::draw_status_screen() { estimation_x_pos = _SD_INFO_X(0); #endif } - else { - strcpy(progress_string, ( - #if ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) - permyriadtostr4(progress) - #else - ui8tostr3rj(progress / (PROGRESS_SCALE)) - #endif - )); - } + else + strcpy(progress_string, TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(progress), ui8tostr3rj(progress / (PROGRESS_SCALE)))); + #if BOTH(SHOW_REMAINING_TIME, ROTATE_PROGRESS_DISPLAY) // Tri-state progress display mode progress_x_pos = _SD_INFO_X(strlen(progress_string) + 1); #endif From 789493773703c7e3d16c747e5a6b6529a2c03e49 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Sun, 12 Apr 2020 21:12:08 +0200 Subject: [PATCH 0140/1454] Update Spanish language (#17505) --- Marlin/src/lcd/language/language_es.h | 114 +++++++++++++------------- 1 file changed, 57 insertions(+), 57 deletions(-) diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 0952dde202..f3a0a353d3 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -66,34 +66,34 @@ namespace Language_es { PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Pulsar para comenzar"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Siguiente punto"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("¡Nivelación lista!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Compensación Altura"); + PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Compen. Altura"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ajustar desfases"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicada"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Establecer origen"); - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Precalentar ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Precalentar ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Fin"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Fin ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Todo"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Cama"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Ajuste"); - PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Precalentar ") PREHEAT_2_LABEL; - PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Precalentar ") PREHEAT_2_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Precalentar ") PREHEAT_2_LABEL _UxGT(" Fin"); - PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Precalentar ") PREHEAT_2_LABEL _UxGT(" Fin ~"); - PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Precalentar ") PREHEAT_2_LABEL _UxGT(" Todo"); - PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Precalentar ") PREHEAT_2_LABEL _UxGT(" Cama"); - PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Precalentar ") PREHEAT_2_LABEL _UxGT(" Ajuste"); - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Precalen. Personali."); + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Precal. ") PREHEAT_1_LABEL; + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Precal. ") PREHEAT_1_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Fusor"); + PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Fusor ~"); + PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Todo"); + PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Cama"); + PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Ajuste"); + PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Precal. ") PREHEAT_2_LABEL; + PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Precal. ") PREHEAT_2_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Precal. ") PREHEAT_2_LABEL _UxGT(" Fusor"); + PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Precal. ") PREHEAT_2_LABEL _UxGT(" Fusor ~"); + PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Precal. ") PREHEAT_2_LABEL _UxGT(" Todo"); + PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Precal. ") PREHEAT_2_LABEL _UxGT(" Cama"); + PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Precal. ") PREHEAT_2_LABEL _UxGT(" Ajuste"); + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Precal. manual"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Enfriar"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Láser Apagado"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Láser Encendido"); + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Apagar Láser"); + PROGMEM Language_Str MSG_LASER_ON = _UxGT("Encender Láser"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Mandrino"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Mandrino Apagado"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Mandrino Encendido"); + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Apagar Mandrino"); + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Encender Mandrino"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Mandrino"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Invertir giro"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Encender Fuente"); @@ -112,22 +112,22 @@ namespace Language_es { PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comandos Personaliz."); + PROGMEM Language_Str MSG_USER_MENU = _UxGT("Com. Personalizados"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Desfase Boquillas"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Desfase Herramienta"); PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Aparcado"); PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicar"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Reflejada"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ª Boquilla X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ª Boquilla Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ª Boquilla Z"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ª Fusor X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ª Fusor Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ª Fusor Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Hacer G29"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Herramientas UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Nivel.Cama.Uni.(UBL)"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Nivelado UBL"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Crear Mallado man."); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Colocar cuña y Medir"); @@ -137,24 +137,24 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Cama"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Cama"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Cama perso."); PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Fusor"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Fusor"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Fusor perso."); PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Mallado"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Mallado perso."); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Ajuste fino Mallado"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Term. edici. Mallado"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Mallado Perso."); + PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Mallado Pers."); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Mallado"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_M1 = _UxGT("Crear Mallado (") PREHEAT_1_LABEL _UxGT(")"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_M2 = _UxGT("Crear Mallado (") PREHEAT_2_LABEL _UxGT(")"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Mallado Frío"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajustar alt. Mallado"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Cantidad de altura"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Mallado"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("Validar Mallado (") PREHEAT_1_LABEL _UxGT(")"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("Validar Mallado (") PREHEAT_2_LABEL _UxGT(")"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Vali. Mallado perso."); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Valid. Mallado"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("Valid. Mall. (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("Valid. Mall. (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valid. Mall. perso."); PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Calentando Cama"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Calent. Boquilla"); PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Imprimado manual..."); @@ -165,7 +165,7 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Contin. Mallado cama"); PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nivelando Mallado"); PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelando 3Puntos"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivel. Mallado cuad."); + PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Niv. Mall. cuadri"); PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivel de Mallado"); PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterales"); PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo de mapa "); @@ -183,9 +183,9 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Ajustar Fino Todo"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ajustar Fino proxi."); PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacen de Mallado"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Huecos de memoria"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Mallado cama"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Guardar Mallado cama"); + PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Huecos memoria"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Mall. cama"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Guardar Mall. cama"); PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malla %i Guardada"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sin guardar"); @@ -194,17 +194,17 @@ namespace Language_es { PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Parado"); PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crear Mallado Frío"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crear Mall. Frío"); PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Relleno intelig."); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Validar Mallado"); + PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Valid. Mallado"); PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ajustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Validar Mallado"); + PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Valid. Mallado"); PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ajustar Fino Todo"); PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Guardar Mall. cama"); PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Control LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Luzes"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Luz predefinida"); + PROGMEM Language_Str MSG_LEDS = _UxGT("LEDS"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Color predefinido"); PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Rojo"); PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Naranja"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Amarillo"); @@ -214,7 +214,7 @@ namespace Language_es { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Blanco"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luces personalizadas"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Color personalizado"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensidad Rojo"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensidad Verde"); PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensidad Azul"); @@ -257,9 +257,9 @@ namespace Language_es { PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Factor"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temperatura Auto."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Encender"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apagar"); + PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temp. Autom."); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("Enc"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apg"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); @@ -280,7 +280,7 @@ namespace Language_es { PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desviación de Unión"); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvi. Unión"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidad"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; @@ -289,7 +289,7 @@ namespace Language_es { PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accel"); + PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleración"); PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Acel. max") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Acel. max") LCD_STR_C; @@ -343,7 +343,7 @@ namespace Language_es { PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimiendo Objeto"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Recuper. por interr."); + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Rec. Fallo electrico"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Imprim. desde SD/USB"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD/USB no presente"); PROGMEM Language_Str MSG_DWELL = _UxGT("Reposo..."); @@ -403,10 +403,10 @@ namespace Language_es { PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Subir Sonda Z"); PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Bajar Sonda Z"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Origen %s%s%s Prim."); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desfase Sonda"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desfase Sonda X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desfase Sonda Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Sonda Z"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desf. Sonda"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desf. Sonda X"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desf. Sonda Y"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desf. Sonda Z"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); @@ -449,7 +449,7 @@ namespace Language_es { PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altura"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radio"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Acerca de Impresora"); + PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Info. Impresora"); PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info. Impresora"); PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelando 3puntos"); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelando Lineal"); @@ -485,7 +485,7 @@ namespace Language_es { PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp. Mínima"); PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fuente alimentación"); + PROGMEM Language_Str MSG_INFO_PSU = _UxGT("F. Aliment."); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Fuerza de empuje"); PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); @@ -501,8 +501,8 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar más"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continuar imp."); PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Boquilla: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor de sección"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist de secc. mm"); + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sens. filamento"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist. filamento mm"); PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Ir a origen Fallado"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondeo Fallado"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Muy Frio"); From a2e9a02429b0a15c88b57dff5b5341601b90685d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Apr 2020 14:43:04 -0500 Subject: [PATCH 0141/1454] Fix PLR when card isn't mounted yet Fixes a regression from 9bff67bc747 --- Marlin/src/feature/powerloss.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index bb0062d4ec..37d82eec6a 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -100,7 +100,7 @@ void PrintJobRecovery::changed() { * If a saved state exists send 'M1000 S' to initiate job recovery. */ void PrintJobRecovery::check() { - //if (!card.isMounted()) card.mount(); + if (!card.isMounted()) card.mount(); if (card.isMounted()) { load(); if (!valid()) return purge(); From ac7b484703fc04afb3232f997b76e64959d8ba9b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Apr 2020 14:58:47 -0500 Subject: [PATCH 0142/1454] Safe homing: Raise Z on G28 Z (#17501) Co-Authored-By: RFBomb --- Marlin/src/gcode/calibrate/G28.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index fafce9a896..3437e33942 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -329,7 +329,7 @@ void GcodeSuite::G28() { ? (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT) : 0; - if (z_homing_height && (doX || doY)) { + if (z_homing_height && (doX || doY || ENABLED(Z_SAFE_HOMING))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) destination.z = z_homing_height + (TEST(axis_known_position, Z_AXIS) ? 0.0f : current_position.z); if (destination.z > current_position.z) { From f090a927f4094f42efea3455314c46c9ff307a64 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Apr 2020 15:16:04 -0500 Subject: [PATCH 0143/1454] Reapply BLTouch deploy/stow patch - Fixes #14328 - Originally #14352 - Reverted in 2580104 --- Marlin/src/module/probe.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 6e3f2baa66..b4912d30c4 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -324,15 +324,13 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { dock_sled(!deploy); + #elif ENABLED(BLTOUCH) + + deploy ? bltouch.deploy() : bltouch.stow(); + #elif HAS_Z_SERVO_PROBE - #if DISABLED(BLTOUCH) - MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][deploy ? 0 : 1]); - #elif ENABLED(BLTOUCH_HS_MODE) - // In HIGH SPEED MODE, use the normal retractable probe logic in this code - // i.e. no intermediate STOWs and DEPLOYs in between individual probe actions - if (deploy) bltouch.deploy(); else bltouch.stow(); - #endif + MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][deploy ? 0 : 1]); #elif EITHER(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY) From e3321920f3bab800812ed0d2395fb00fe80072fb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Apr 2020 17:21:02 -0500 Subject: [PATCH 0144/1454] Update Marlin website links to https --- .github/contributing.md | 8 ++++---- Marlin/Configuration.h | 4 ++-- Marlin/Configuration_adv.h | 4 ++-- Marlin/Marlin.ino | 8 ++++---- Marlin/src/core/language.h | 2 +- Marlin/src/feature/twibus.h | 4 ++-- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/lcd/dogm/dogm_Bootscreen.h | 2 +- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 2 +- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 2 +- Marlin/src/lcd/language/language_an.h | 2 +- Marlin/src/lcd/language/language_bg.h | 2 +- Marlin/src/lcd/language/language_ca.h | 2 +- Marlin/src/lcd/language/language_cz.h | 2 +- Marlin/src/lcd/language/language_da.h | 2 +- Marlin/src/lcd/language/language_de.h | 2 +- Marlin/src/lcd/language/language_el.h | 2 +- Marlin/src/lcd/language/language_el_gr.h | 2 +- Marlin/src/lcd/language/language_en.h | 2 +- Marlin/src/lcd/language/language_es.h | 2 +- Marlin/src/lcd/language/language_eu.h | 2 +- Marlin/src/lcd/language/language_fi.h | 2 +- Marlin/src/lcd/language/language_fr.h | 2 +- Marlin/src/lcd/language/language_gl.h | 2 +- Marlin/src/lcd/language/language_hr.h | 2 +- Marlin/src/lcd/language/language_it.h | 2 +- Marlin/src/lcd/language/language_jp_kana.h | 2 +- Marlin/src/lcd/language/language_ko_KR.h | 2 +- Marlin/src/lcd/language/language_nl.h | 2 +- Marlin/src/lcd/language/language_pl.h | 2 +- Marlin/src/lcd/language/language_pt.h | 2 +- Marlin/src/lcd/language/language_pt_br.h | 2 +- Marlin/src/lcd/language/language_ru.h | 2 +- Marlin/src/lcd/language/language_sk.h | 2 +- Marlin/src/lcd/language/language_test.h | 2 +- Marlin/src/lcd/language/language_tr.h | 2 +- Marlin/src/lcd/language/language_uk.h | 2 +- Marlin/src/lcd/language/language_vi.h | 2 +- Marlin/src/lcd/language/language_zh_CN.h | 2 +- Marlin/src/lcd/language/language_zh_TW.h | 2 +- README.md | 6 +++--- buildroot/share/fonts/uxggenpages.md | 2 +- buildroot/share/git/mfpub | 2 +- 43 files changed, 54 insertions(+), 54 deletions(-) diff --git a/.github/contributing.md b/.github/contributing.md index 808c87bb04..589f14581a 100644 --- a/.github/contributing.md +++ b/.github/contributing.md @@ -93,7 +93,7 @@ Before creating a suggestion, please check [this list](#before-submitting-a-sugg #### Before Submitting a Feature Request -* **Check the [Marlin website](http://marlinfw.org/)** for tips — you might discover that the feature is already included. Most importantly, check if you're using [the latest version of Marlin](https://github.com/MarlinFirmware/Marlin/releases) and if you can get the desired behavior by changing [Marlin's config settings](http://marlinfw.org/docs/configuration/configuration.html). +* **Check the [Marlin website](https://marlinfw.org/)** for tips — you might discover that the feature is already included. Most importantly, check if you're using [the latest version of Marlin](https://github.com/MarlinFirmware/Marlin/releases) and if you can get the desired behavior by changing [Marlin's config settings](https://marlinfw.org/docs/configuration/configuration.html). * **Perform a [cursory search](https://github.com/MarlinFirmware/Marlin/issues?q=is%3Aissue)** to see if the enhancement has already been suggested. If it has, add a comment to the existing issue instead of opening a new one. #### How Do I Submit A (Good) Feature Request? @@ -117,12 +117,12 @@ Unsure where to begin contributing to Marlin? You can start by looking through t ### Pull Requests -Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x` and/or `bugfix-2.0.x`) and never to release branches (e.g., `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](http://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation. +Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x` and/or `bugfix-2.0.x`) and never to release branches (e.g., `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation. * Fill in [the required template](pull_request_template.md). * Don't include issue numbers in the PR title. * Include pictures, diagrams, and links to videos in your Pull Request to demonstrate your changes, if needed. -* Follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) posted on our website. +* Follow the [Coding Standards](https://marlinfw.org/docs/development/coding_standards.html) posted on our website. * Document new code with clear and concise comments. * End all files with a newline. @@ -137,7 +137,7 @@ Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x ### C++ Coding Standards -* Please read and follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) posted on our website. Failure to follow these guidelines will delay evaluation and acceptance of Pull Requests. +* Please read and follow the [Coding Standards](https://marlinfw.org/docs/development/coding_standards.html) posted on our website. Failure to follow these guidelines will delay evaluation and acceptance of Pull Requests. ### Documentation diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 175a5fbef3..b0a0f8ebb8 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -820,7 +820,7 @@ // @section probes // -// See http://marlinfw.org/docs/configuration/probes.html +// See https://marlinfw.org/docs/configuration/probes.html // /** @@ -1636,7 +1636,7 @@ * - Click the controller to view the LCD menu * - The LCD will display Japanese, Western, or Cyrillic text * - * See http://marlinfw.org/docs/development/lcd_language.html + * See https://marlinfw.org/docs/development/lcd_language.html * * :['JAPANESE', 'WESTERN', 'CYRILLIC'] */ diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 82cf3e1949..6cc9f01ffc 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1508,7 +1508,7 @@ * If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk) * print acceleration will be reduced during the affected moves to keep within the limit. * - * See http://marlinfw.org/docs/features/lin_advance.html for full instructions. + * See https://marlinfw.org/docs/features/lin_advance.html for full instructions. * Mention @Sebastianv650 on GitHub to alert the author of any issues. */ //#define LIN_ADVANCE @@ -2643,7 +2643,7 @@ * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V * hardware PWM pin for the speed control and a pin for the rotation direction. * - * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + * See https://marlinfw.org/docs/configuration/laser_spindle.html for more config details. */ //#define SPINDLE_FEATURE //#define LASER_FEATURE diff --git a/Marlin/Marlin.ino b/Marlin/Marlin.ino index ae5bca1dfe..6f8842cc0b 100644 --- a/Marlin/Marlin.ino +++ b/Marlin/Marlin.ino @@ -19,7 +19,7 @@ Before diving in, we recommend the following essential links: Marlin Firmware Official Website - - http://marlinfw.org/ + - https://marlinfw.org/ The official Marlin Firmware website contains the most up-to-date documentation. Contributions are always welcome! @@ -30,7 +30,7 @@ Configuration (Applies to Marlin 1.0.x, so Jerk and Acceleration should be halved.) Also... https://www.google.com/search?tbs=vid%3A1&q=configure+marlin - - http://marlinfw.org/docs/configuration/configuration.html + - https://marlinfw.org/docs/configuration/configuration.html Marlin's configuration options are explained in more detail here. Getting Help @@ -45,9 +45,9 @@ Getting Help Contributing - - http://marlinfw.org/docs/development/contributing.html + - https://marlinfw.org/docs/development/contributing.html If you'd like to contribute to Marlin, read this first! - - http://marlinfw.org/docs/development/coding_standards.html + - https://marlinfw.org/docs/development/coding_standards.html Before submitting code get to know the Coding Standards. */ diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index a166de59ca..f4205d3f64 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -39,7 +39,7 @@ // // ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRA_LCD" / "SDSUPPORT" #define IN "Configuration.h" // ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS -// See also http://marlinfw.org/docs/development/lcd_language.html +// See also https://marlinfw.org/docs/development/lcd_language.html // Languages // an Aragonese diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 2c1b20da51..609693d879 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -46,8 +46,8 @@ typedef void (*twiRequestFunc_t)(); * for the host to interpret. * * For more information see - * - http://marlinfw.org/docs/gcode/M260.html - * - http://marlinfw.org/docs/gcode/M261.html + * - https://marlinfw.org/docs/gcode/M260.html + * - https://marlinfw.org/docs/gcode/M261.html * */ class TWIBus { diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 8e5d054d99..315b080e33 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -31,7 +31,7 @@ * ----------------- * * Helpful G-code references: - * - http://marlinfw.org/meta/gcode + * - https://marlinfw.org/meta/gcode * - https://reprap.org/wiki/G-code * - http://linuxcnc.org/docs/html/gcode.html * diff --git a/Marlin/src/lcd/dogm/dogm_Bootscreen.h b/Marlin/src/lcd/dogm/dogm_Bootscreen.h index f4bf5f5f69..0d90736c6d 100644 --- a/Marlin/src/lcd/dogm/dogm_Bootscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Bootscreen.h @@ -25,7 +25,7 @@ * Standard Marlin Boot Screen bitmaps * * Use the Marlin Bitmap Converter to make your own: - * http://marlinfw.org/tools/u8glib/converter.html + * https://marlinfw.org/tools/u8glib/converter.html */ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 3384f5798a..8295e9e058 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -25,7 +25,7 @@ * Standard Marlin Status Screen bitmaps * * Use the Marlin Bitmap Converter to make your own: - * http://marlinfw.org/tools/u8glib/converter.html + * https://marlinfw.org/tools/u8glib/converter.html */ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index 4e07999bf6..0a7064f17a 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -65,7 +65,7 @@ /** * Include all needed font files - * (See http://marlinfw.org/docs/development/fonts.html) + * (See https://marlinfw.org/docs/development/fonts.html) */ #include "fontdata/fontdata_ISO10646_1.h" #if ENABLED(USE_SMALL_INFOFONT) diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 8e7798d72d..fb2a2277b7 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -25,7 +25,7 @@ * Aragonese * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 1987c20766..686cf42514 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -25,7 +25,7 @@ * Bulgarian * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index ef5334f878..6cab7ce1e3 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -25,7 +25,7 @@ * Catalan * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_ca { diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index caa458402a..1b800e7bef 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -26,7 +26,7 @@ * UTF-8 for Graphical Display * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * * Translated by Petr Zahradnik, Computer Laboratory * Blog and video blog Zahradnik se bavi diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 23d931c174..8ef9f2239c 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -25,7 +25,7 @@ * Danish * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index aa3f0a5f01..f31d967289 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -25,7 +25,7 @@ * German * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 6cb177d108..1e141548fe 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -25,7 +25,7 @@ * Greek * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index 5213dc7db9..fc4b805958 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -25,7 +25,7 @@ * Greek (Greece) * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f9a9671bb2..f2be60c72d 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -25,7 +25,7 @@ * English * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index f3a0a353d3..6bc2525f19 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -25,7 +25,7 @@ * Spanish * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index a6a0a52518..32c6e0f001 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -25,7 +25,7 @@ * Basque-Euskera * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 79124c0007..0259767875 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -25,7 +25,7 @@ * Finnish * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 6196f40c64..2b853927c7 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -25,7 +25,7 @@ * French * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index d9d07f8ec2..d1eac052f9 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -25,7 +25,7 @@ * Galician language (ISO "gl") * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 740d7e5625..8b98de5818 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -25,7 +25,7 @@ * Croatian (Hrvatski) * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 84438f2847..5e29d4b051 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -25,7 +25,7 @@ * Italian * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 809ee83de8..ce594f7c22 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -26,7 +26,7 @@ * UTF-8 for Graphical Display * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_ko_KR.h b/Marlin/src/lcd/language/language_ko_KR.h index 4d8142e38b..344e8243ac 100644 --- a/Marlin/src/lcd/language/language_ko_KR.h +++ b/Marlin/src/lcd/language/language_ko_KR.h @@ -25,7 +25,7 @@ * Korean * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_ko_KR { diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index d5d46ecfe6..a87f6cda2f 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -25,7 +25,7 @@ * Dutch * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 469bed05b1..88b3295a23 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -25,7 +25,7 @@ * Polish - includes accented characters * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 69c8be603f..412c3256af 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -26,7 +26,7 @@ * UTF-8 for Graphical Display * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 8fd771ab05..1272e2200c 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -26,7 +26,7 @@ * UTF-8 for Graphical Display * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_pt_br { diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 8d2a722b19..34eea736be 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -25,7 +25,7 @@ * Russian * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ #define DISPLAY_CHARSET_ISO10646_5 diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 6f7707421e..16854dcd59 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -26,7 +26,7 @@ * UTF-8 for Graphical Display * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * * Translated by Michal Holeš, Farma MaM * http://www.facebook.com/farmamam diff --git a/Marlin/src/lcd/language/language_test.h b/Marlin/src/lcd/language/language_test.h index 465d3743f3..147379f5bd 100644 --- a/Marlin/src/lcd/language/language_test.h +++ b/Marlin/src/lcd/language/language_test.h @@ -25,7 +25,7 @@ * TEST * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 7db3592902..d847d5496f 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -25,7 +25,7 @@ * Turkish * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * * Bu çeviri dosyasındaki sorunlar ve düzeltmeler için iletişim; * Contact for issues and corrections in this translation file; diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 0d473bf0af..44f3401d6e 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -25,7 +25,7 @@ * Ukrainian * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 8d13fdb194..dc90e85ce2 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -25,7 +25,7 @@ * Vietnamese * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_vi { diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 0207c47baa..48bcfc0819 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -25,7 +25,7 @@ * Simplified Chinese * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_zh_CN { diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index a0812a89f3..53e40bbab8 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -25,7 +25,7 @@ * Traditional Chinese * * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html + * See also https://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_zh_TW { diff --git a/README.md b/README.md index ffb3de097d..6011d5e243 100644 --- a/README.md +++ b/README.md @@ -7,7 +7,7 @@ -Additional documentation can be found at the [Marlin Home Page](http://marlinfw.org/). +Additional documentation can be found at the [Marlin Home Page](https://marlinfw.org/). Please test this firmware and let us know if it misbehaves in any way. Volunteers are standing by! ## Marlin 2.0 Bugfix Branch @@ -22,7 +22,7 @@ Download earlier versions of Marlin on the [Releases page](https://github.com/Ma ## Building Marlin 2.0 -To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino.cc/en/main/software) or [PlatformIO](http://docs.platformio.org/en/latest/ide.html#platformio-ide). We've posted detailed instructions on [Building Marlin with Arduino](http://marlinfw.org/docs/basics/install_arduino.html) and [Building Marlin with PlatformIO for ReArm](http://marlinfw.org/docs/basics/install_rearm.html) (which applies well to other 32-bit boards). +To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino.cc/en/main/software) or [PlatformIO](http://docs.platformio.org/en/latest/ide.html#platformio-ide). We've posted detailed instructions on [Building Marlin with Arduino](https://marlinfw.org/docs/basics/install_arduino.html) and [Building Marlin with PlatformIO for ReArm](https://marlinfw.org/docs/basics/install_rearm.html) (which applies well to other 32-bit boards). ## Hardware Abstraction Layer (HAL) @@ -95,7 +95,7 @@ Marlin 2.0 introduces a layer of abstraction so that all the existing high-level Proposed patches should be submitted as a Pull Request against the ([bugfix-2.0.x](https://github.com/MarlinFirmware/Marlin/tree/bugfix-2.0.x)) branch. - This branch is for fixing bugs and integrating any new features for the duration of the Marlin 2.0.x life-cycle. -- Follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) to gain points with the maintainers. +- Follow the [Coding Standards](https://marlinfw.org/docs/development/coding_standards.html) to gain points with the maintainers. - Please submit your questions and concerns to the [Issue Queue](https://github.com/MarlinFirmware/Marlin/issues). ### [RepRap.org Wiki Page](http://reprap.org/wiki/Marlin) diff --git a/buildroot/share/fonts/uxggenpages.md b/buildroot/share/fonts/uxggenpages.md index 314b5d5c06..c2d94735c7 100644 --- a/buildroot/share/fonts/uxggenpages.md +++ b/buildroot/share/fonts/uxggenpages.md @@ -104,7 +104,7 @@ At this time, the font file `marlin-6x12-3.bdf` is used to generate the font dat Documents related to the old version of the language engine: - [Marlin Fonts Documentation](http://www.marlinfw.org/docs/development/fonts.html) -- [Marlin LCD Language](http://marlinfw.org/docs/development/lcd_language.html) +- [Marlin LCD Language](https://marlinfw.org/docs/development/lcd_language.html) - [U8GLIB](https://github.com/olikraus/u8glib.git) - [UTF-8 for U8GLIB](https://github.com/yhfudev/u8glib-fontutf8.git) - [Standalone test project for the Marlin UTF-8 language engine](https://github.com/yhfudev/marlin-fontutf8.git) diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 53911d6d4e..ab43b70672 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -126,7 +126,7 @@ git push -f origin git push -f upstream | { while IFS= read -r line do - [[ $line =~ "gh-pages -> gh-pages" ]] && opensite "http://marlinfw.org/" + [[ $line =~ "gh-pages -> gh-pages" ]] && opensite "https://marlinfw.org/" echo "$line" done } From a7a76f123df7a869319532e017e8edf1f9d9cc17 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 13 Apr 2020 00:03:48 +0000 Subject: [PATCH 0145/1454] [cron] Bump distribution date (2020-04-13) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6ffec1d458..dc7a10c184 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-12" + #define STRING_DISTRIBUTION_DATE "2020-04-13" #endif /** From 22da1b2b310158ae3362c54f2534f5f5af30fa83 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Apr 2020 14:53:21 -0500 Subject: [PATCH 0146/1454] Rename some "kill" messages --- Marlin/src/feature/mmu2/mmu2.cpp | 2 +- Marlin/src/gcode/host/M16.cpp | 2 +- Marlin/src/lcd/language/language_bg.h | 2 +- Marlin/src/lcd/language/language_ca.h | 2 +- Marlin/src/lcd/language/language_cz.h | 6 +++--- Marlin/src/lcd/language/language_da.h | 2 +- Marlin/src/lcd/language/language_de.h | 6 +++--- Marlin/src/lcd/language/language_el.h | 2 +- Marlin/src/lcd/language/language_el_gr.h | 2 +- Marlin/src/lcd/language/language_en.h | 6 +++--- Marlin/src/lcd/language/language_es.h | 6 +++--- Marlin/src/lcd/language/language_eu.h | 4 ++-- Marlin/src/lcd/language/language_fi.h | 2 +- Marlin/src/lcd/language/language_fr.h | 4 ++-- Marlin/src/lcd/language/language_gl.h | 6 +++--- Marlin/src/lcd/language/language_hr.h | 2 +- Marlin/src/lcd/language/language_it.h | 6 +++--- Marlin/src/lcd/language/language_jp_kana.h | 2 +- Marlin/src/lcd/language/language_ko_KR.h | 2 +- Marlin/src/lcd/language/language_nl.h | 2 +- Marlin/src/lcd/language/language_pl.h | 6 +++--- Marlin/src/lcd/language/language_pt.h | 2 +- Marlin/src/lcd/language/language_pt_br.h | 4 ++-- Marlin/src/lcd/language/language_ru.h | 4 ++-- Marlin/src/lcd/language/language_sk.h | 6 +++--- Marlin/src/lcd/language/language_tr.h | 6 +++--- Marlin/src/lcd/language/language_uk.h | 2 +- Marlin/src/lcd/language/language_vi.h | 2 +- Marlin/src/lcd/language/language_zh_CN.h | 4 ++-- Marlin/src/lcd/language/language_zh_TW.h | 6 +++--- Marlin/src/module/endstops.cpp | 2 +- 31 files changed, 56 insertions(+), 56 deletions(-) diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 4506883f46..27b7f99205 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -433,7 +433,7 @@ bool MMU2::rx_ok() { void MMU2::check_version() { if (buildnr < MMU_REQUIRED_FW_BUILDNR) { SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); - kill(GET_TEXT(MSG_MMU2_WRONG_FIRMWARE)); + kill(GET_TEXT(MSG_KILL_MMU2_FIRMWARE)); } } diff --git a/Marlin/src/gcode/host/M16.cpp b/Marlin/src/gcode/host/M16.cpp index fd3320db93..996ce7c419 100644 --- a/Marlin/src/gcode/host/M16.cpp +++ b/Marlin/src/gcode/host/M16.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M16() { if (strcmp_P(parser.string_arg, PSTR(MACHINE_NAME))) - kill(GET_TEXT(MSG_EXPECTED_PRINTER)); + kill(GET_TEXT(MSG_KILL_EXPECTED_PRINTER)); } diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 686cf42514..aa7875e44b 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -149,5 +149,5 @@ namespace Language_bg { PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровка Y"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калибровка Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калибровка Център"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Неправилен принтер"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неправилен принтер"); } diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 6cab7ce1e3..66b061c6ab 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -211,7 +211,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Repren impressió"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impressora incorrecta"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora incorrecta"); // // Filament Change screens show up to 3 lines on a 4-line display diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 1b800e7bef..7fffc21806 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -464,7 +464,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Osvětlení"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas světla"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("NESPRÁVNÁ TISKÁRNA"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("NESPRÁVNÁ TISKÁRNA"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Počet tisků"); @@ -500,13 +500,13 @@ namespace Language_cz { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Délka mm senz.fil."); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Parkování selhalo"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkování selhalo"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrace selhala"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Moc studený"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Aktual. MMU firmware!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Aktual. MMU firmware!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU potř. pozornost."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Obnovit tisk"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Obnovování..."); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 8ef9f2239c..0ecb583e80 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -185,7 +185,7 @@ namespace Language_da { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Forsæt print"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Forkert printer"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Forkert printer"); #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Vent på start", "af filament", "skift")); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index f31d967289..f4fe9d1cff 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -433,7 +433,7 @@ namespace Language_de { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Beleuchtung"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Helligkeit"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Gesamte Drucke"); @@ -469,13 +469,13 @@ namespace Language_de { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Düse: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Runout-Sensor"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout-Weg mm"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Homing gescheitert"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing gescheitert"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing gescheitert"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: zu kalt"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMENT WÄHLEN"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Update MMU Firmware!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU handeln erfor."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Druck fortsetzen"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Fortfahren..."); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 1e141548fe..17e4e819c1 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -188,5 +188,5 @@ namespace Language_el { PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Βαθμονόμηση Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Βαθμονόμηση κέντρου"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); } diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index fc4b805958..d107f42f7b 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -189,5 +189,5 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Βαθμονόμηση Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Βαθμονόμηση κέντρου"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f2be60c72d..7f04025671 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -473,7 +473,7 @@ namespace Language_en { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case Light"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Print Count"); @@ -509,13 +509,13 @@ namespace Language_en { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Runout Sensor"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Homing Failed"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Too Cold"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Update MMU Firmware!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Resume Print"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resuming..."); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 6bc2525f19..dd06ac5dcc 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -467,7 +467,7 @@ namespace Language_es { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz cabina"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo cabina"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Cont. de impresión"); @@ -503,13 +503,13 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Boquilla: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sens. filamento"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist. filamento mm"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Ir a origen Fallado"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Ir a origen Fallado"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondeo Fallado"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Muy Frio"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ELIJE FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("¡Actu. MMU Firmware!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("¡Actu. MMU Firmware!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Necesita Cuidado"); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Continuar imp."); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resumiendo..."); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 32c6e0f001..ed065559b6 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -306,11 +306,11 @@ namespace Language_eu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ALDAKETA AUKERAK:"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Inprima. jarraitu"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Pita: "); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Hasi. huts egin du"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Hasi. huts egin du"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Neurketak huts egin du"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: hotzegi"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Inprimagailu okerra"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Inprimagailu okerra"); // // Filament Change screens show up to 3 lines on a 4-line display diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 0259767875..59bdf8d6d6 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -124,5 +124,5 @@ namespace Language_fi { PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibroi Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibroi Center"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Väärä tulostin"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Väärä tulostin"); } diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 2b853927c7..fa4c3c66ed 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -422,7 +422,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Lumière caisson"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosité"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Imprimante incorrecte"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Imprimante incorrecte"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nbre impressions"); @@ -458,7 +458,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Reprendre impr."); PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Buse: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Capteur fil."); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Echec origine"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Echec origine"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Echec sonde"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Trop froid"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index d1eac052f9..958fd0a32c 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -470,7 +470,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz da Caixa"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo Luces"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total Impresións"); @@ -506,13 +506,13 @@ namespace Language_gl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bico: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor Filamento"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm Sensor Fil"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Fallo ao Sondar"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Moi Frío"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLLE FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Actualizar FW MMU!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Actualizar FW MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Precisa Atención."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Retomar impr."); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Retomando..."); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 8b98de5818..e50d4b8d77 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -132,7 +132,7 @@ namespace Language_hr { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Osvjetljenje"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Neispravan pisač"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Neispravan pisač"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Broj printova"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 5e29d4b051..1870957401 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -501,13 +501,13 @@ namespace Language_it { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Ugello: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Home fallito"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600:Troppo freddo"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SCELTA FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Agg.firmware MMU!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Agg.firmware MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU chiede attenz."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Riprendi stampa"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Ripresa..."); @@ -551,7 +551,7 @@ namespace Language_it { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Stampante errata"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Stampante errata"); // // Le schermate di Cambio Filamento possono visualizzare fino a 3 linee su un display a 4 righe diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index ce594f7c22..62b7daf705 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -228,7 +228,7 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("フィラメントソウテンチュウ", "シバラクオマチクダサイ")); // "Wait for filament load" PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("プリントヲサイカイシマス", "シバラクオマチクダサイ")); // "Wait for print to resume" - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("マチガッタプリンター"); // "Wrong printer" + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("マチガッタプリンター"); // "Wrong printer" PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("セッテイカンリ"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("ショウサイセッテイ"); diff --git a/Marlin/src/lcd/language/language_ko_KR.h b/Marlin/src/lcd/language/language_ko_KR.h index 344e8243ac..8d022e99c0 100644 --- a/Marlin/src/lcd/language/language_ko_KR.h +++ b/Marlin/src/lcd/language/language_ko_KR.h @@ -100,5 +100,5 @@ namespace Language_ko_KR { PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("취소됨"); PROGMEM Language_Str MSG_KILLED = _UxGT("죽음. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("멈춤. "); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("잘못된 프린터"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("잘못된 프린터"); } diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index a87f6cda2f..5742d15ef1 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -193,7 +193,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocol"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case licht"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Onjuiste printer"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Onjuiste printer"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Printed Aantal"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 88b3295a23..b8b48bc480 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -437,7 +437,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Niepoprawna drukarka"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Niepoprawna drukarka"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Wydrukowano"); @@ -473,13 +473,13 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Dysza: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Czujnik filamentu"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dystans do czujnika mm"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Zerowanie nieudane"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Zerowanie nieudane"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: za zimne"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Wznawianie..."); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 412c3256af..bc7465716c 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -159,5 +159,5 @@ namespace Language_pt { PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Fim de curso"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); } diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 1272e2200c..469b75e823 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -359,7 +359,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz da Impressora"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Intensidade Brilho"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total de Impressões"); @@ -389,7 +389,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continuar Impressão"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bocal: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor filamento"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Falha ao ir à origem"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Falha ao ir à origem"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Falha ao sondar"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Muito frio"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 34eea736be..69d9d61207 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -407,7 +407,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Подсветка корпуса"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Неверный принтер"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); @@ -438,7 +438,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Выдавить ещё"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Возобновить печать"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопла: "); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Возврат не удался"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Возврат не удался"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Не удалось прощупать"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Низкая Т"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 16854dcd59..53602af7c5 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -453,7 +453,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Osvetlenie"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas svetla"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Počet tlačí"); @@ -489,13 +489,13 @@ namespace Language_sk { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Príliš studený"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU2"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Aktualizujte FW MMU!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Aktualizujte FW MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU potrebuje zásah."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Obnoviť tlač"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Obnovovanie..."); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index d847d5496f..e1d3bd898c 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -463,7 +463,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Aydınlatmayı Aç"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Aydınlatma Parlaklğı"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Yanlış Yazıcı"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Yanlış Yazıcı"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Baskı Sayısı"); @@ -499,13 +499,13 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozul: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Runout Sensörü"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Aşınma Farkı mm"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Sıfırlama Başarısız"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Sıfırlama Başarısız"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Başarısız"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Çok Soğuk"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMAN SEÇ"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("MMU Yaz. Güncelle!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU Yaz. Güncelle!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Dikkat Gerektirir."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Yaz. Devam Et"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Sürdürülüyor..."); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 44f3401d6e..c5d85fe6bf 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -194,7 +194,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Протокол"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Підсвітка"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Неправильний принтер"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неправильний принтер"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("К-сть друків"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index dc90e85ce2..71c8eebdd8 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -403,7 +403,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Tiếp tục"); // continue PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Đầu Phun: "); // Nozzle PROGMEM Language_Str MSG_RUNOUT_SENSOR_ENABLE = _UxGT("Cảm Biến Hết"); // Runout Sensor - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Sự nhà không thành công"); // Homing failed + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Sự nhà không thành công"); // Homing failed PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT(" không thành công"); // Probing failed PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Quá lạnh"); diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 48bcfc0819..bb30b775bf 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -331,7 +331,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("外壳灯"); // "Case light" PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("灯亮度"); // "Light BRIGHTNESS" - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("打印机不正确"); // "The printer is incorrect" + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("打印机不正确"); // "The printer is incorrect" #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印计数"); //"Print Count" @@ -363,7 +363,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("清除更多"); // "Purge more" PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("恢复打印"); //"Resume print" PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" 喷嘴: "); // " Nozzle: " - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("归原位失败"); // "Homing failed" + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("归原位失败"); // "Homing failed" PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探针探测失败"); // "Probing failed" PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: 太凉"); // "M600: Too cold" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 53e40bbab8..0c6f69ebba 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -459,7 +459,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("外殼燈"); // "Case light" PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("燈亮度"); // "Light BRIGHTNESS" - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印計數"); //"Print Count" @@ -496,13 +496,13 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" 噴嘴: "); // " Nozzle: " PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("斷絲偵測"); //"Runout Sensor" PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("絲距離mm"); //"Runout Dist mm" - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: 太冷"); // "M600: Too cold" PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Update MMU Firmware!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Resume Print"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resuming..."); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 1c8384cc53..f55d56b959 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -325,7 +325,7 @@ void Endstops::not_homing() { // If the last move failed to trigger an endstop, call kill void Endstops::validate_homing_move() { if (trigger_state()) hit_on_purpose(); - else kill(GET_TEXT(MSG_LCD_HOMING_FAILED)); + else kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); } #endif From e6ccec17a6a0d78983930e1d00822e21eeea2aca Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Apr 2020 14:41:57 -0500 Subject: [PATCH 0147/1454] Expose SD_PROCEDURE_DEPTH in config --- Marlin/Configuration_adv.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6cc9f01ffc..fbfe63036e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1035,6 +1035,8 @@ // Enable this option and set to HIGH if your SD cards are incorrectly detected. //#define SD_DETECT_STATE HIGH + #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls + #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished #define SD_FINISHED_RELEASECOMMAND "M84" // Use "M84XYE" to keep Z enabled so your bed stays in place From 421825259e5ccbde6f4b682279555123b020c872 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Apr 2020 14:42:32 -0500 Subject: [PATCH 0148/1454] Shorter M32 error message --- Marlin/src/sd/cardreader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 63607f7bbd..7acb68670f 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -519,7 +519,7 @@ void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0* // Too deep? The firmware has to bail. if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { - SERIAL_ERROR_MSG("trying to call sub-gcode files with too many levels. MAX level is:" STRINGIFY(SD_PROCEDURE_DEPTH)); + SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:" STRINGIFY(SD_PROCEDURE_DEPTH)); kill(); return; } From e9c8da35c503e68d537091ef2265f5e906bbdbc2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Apr 2020 14:54:05 -0500 Subject: [PATCH 0149/1454] Subcall overflow error message --- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/sd/cardreader.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 7f04025671..fad678eada 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -52,6 +52,7 @@ namespace Language_en { PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Media read error"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB start failed"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); PROGMEM Language_Str MSG_MAIN = _UxGT("Main"); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 7acb68670f..1c8c581b3c 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -520,7 +520,7 @@ void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0* // Too deep? The firmware has to bail. if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:" STRINGIFY(SD_PROCEDURE_DEPTH)); - kill(); + kill(GET_TEXT(MSG_KILL_SUBCALL_OVERFLOW)); return; } From 6ce0c94d125c62107f65a373bf7fd8e6337e9e4f Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Mon, 13 Apr 2020 18:23:54 -0400 Subject: [PATCH 0150/1454] Fix bad comparison (#17470) * Suggested message change * Fix Bad Comparison Co-authored-by: Scott Lahteine --- Marlin/src/module/tool_change.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 658671fb7e..b30e72eace 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -821,7 +821,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool >= EXTRUDERS) return invalid_extruder_error(new_tool); - if (!no_move && !homing_needed()) { + if (!no_move && homing_needed()) { no_move = true; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("No move (not homed)"); } From f59c0ab842b8c4967177d63dcdc91c157d22b84a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 14 Apr 2020 00:08:34 +0000 Subject: [PATCH 0151/1454] [cron] Bump distribution date (2020-04-14) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index dc7a10c184..73a5ef2ea1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-13" + #define STRING_DISTRIBUTION_DATE "2020-04-14" #endif /** From 90382787350b0a135495b1e5d37e5929a89f0fb9 Mon Sep 17 00:00:00 2001 From: Brais Fortes Date: Tue, 14 Apr 2020 04:17:01 +0200 Subject: [PATCH 0152/1454] Galician language corrections (#17454) --- Marlin/src/lcd/language/language_gl.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 958fd0a32c..1fb430bfb6 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -30,7 +30,6 @@ */ #define DISPLAY_CHARSET_ISO10646_1 -#define NOT_EXTENDED_ISO10646_1_5X7 namespace Language_gl { using namespace Language_en; // Inherit undefined strings from English @@ -324,6 +323,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Erro: CRC EEPROM"); PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Erro: Índice EEPROM"); PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Erro: Versión EEPROM"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Config Gardada"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reiniciar Impresora"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); @@ -340,6 +340,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Listo"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Atrás"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceder"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausando..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Retomar impresión"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Deter impresión"); @@ -350,8 +351,8 @@ namespace Language_gl { PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Tarxeta SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Sen tarxeta SD"); PROGMEM Language_Str MSG_DWELL = _UxGT("En repouso..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("A espera..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Prema para Retomar"); + PROGMEM Language_Str MSG_USERWAIT = _UxGT("Prema para Retomar.."); + PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimindo..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impresión Cancelada"); PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Fin Impresión"); From c834b313a5fb90e9fa51b7fcd199376e365c250b Mon Sep 17 00:00:00 2001 From: Axel Date: Mon, 13 Apr 2020 22:49:55 -0400 Subject: [PATCH 0153/1454] Fix Mightyboard build (#17537) --- Marlin/src/feature/digipot/digipot_mcp4018.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index ebfbee794a..675b3e38f0 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -25,7 +25,6 @@ #if BOTH(DIGIPOT_I2C, DIGIPOT_MCP4018) #include -#include #include //https://github.com/stawel/SlowSoftI2CMaster // Settings for the I2C based DIGIPOT (MCP4018) based on WT150 From 3cdc9b81568316958c288f9bd90b441b9501b90d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 15 Apr 2020 00:03:14 +0000 Subject: [PATCH 0154/1454] [cron] Bump distribution date (2020-04-15) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 73a5ef2ea1..4bfe64299c 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-14" + #define STRING_DISTRIBUTION_DATE "2020-04-15" #endif /** From cae2b7bf4e9995f26e919a6a1534c0bd3473a717 Mon Sep 17 00:00:00 2001 From: Alexander Amelkin Date: Wed, 15 Apr 2020 03:03:59 +0300 Subject: [PATCH 0155/1454] SKR Pro V1.1 StallGuard pins (#17550) Co-authored-by: Scott Lahteine --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 12 ++--- .../src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 52 ++++++++++++++++--- 2 files changed, 50 insertions(+), 14 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index c4226001e6..94d90c30d1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -31,18 +31,18 @@ //#define SDCARD_EEPROM_EMULATION #endif -/** - * Trinamic Stallguard pins - */ +// +// Trinamic Stallguard pins +// #define X_DIAG_PIN P1_29 // X- #define Y_DIAG_PIN P1_27 // Y- #define Z_DIAG_PIN P1_25 // Z- #define E0_DIAG_PIN P1_28 // X+ #define E1_DIAG_PIN P1_26 // Y+ -/** - * Limit Switches - */ +// +// Limit Switches +// #if X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 4dbdf0e77f..2755771030 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -39,17 +39,53 @@ #define SERVO0_PIN PA1 // -// Limit Switches +// Trinamic Stallguard pins // -#define X_MIN_PIN PB10 -#define X_MAX_PIN PE15 -#define Y_MIN_PIN PE12 -#define Y_MAX_PIN PE10 -#define Z_MIN_PIN PG8 -#define Z_MAX_PIN PG5 +#define X_DIAG_PIN PB10 // X- +#define Y_DIAG_PIN PE12 // Y- +#define Z_DIAG_PIN PG8 // Z- // -// Z Probe must be this pins +// Limit Switches +// +#if X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_DIR < 0 + #define X_MAX_PIN PE15 // E0 + #else + #define X_MIN_PIN PE15 // E0 + #endif +#else + #define X_MIN_PIN PB10 // X- + #define X_MAX_PIN PE15 // E0 +#endif + +#if Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_DIR < 0 + #define Y_MAX_PIN PE10 // E1 + #else + #define Y_MIN_PIN PE10 // E1 + #endif +#else + #define Y_MIN_PIN PE12 // Y- + #define Y_MAX_PIN PE10 // E1 +#endif + +#if Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_DIR < 0 + #define Z_MAX_PIN PG5 // E2 + #else + #define Z_MIN_PIN PG5 // E2 + #endif +#else + #define Z_MIN_PIN PG8 // Z- + #define Z_MAX_PIN PG5 // E2 +#endif + +// +// Z Probe must be this pin // #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN PA2 From cdbc7cc52c9bc0f1889384e8db2dc46a93f3fb94 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 14 Apr 2020 19:08:55 -0500 Subject: [PATCH 0156/1454] Define En DIAG pins for auto-assigns --- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 2755771030..77acbc5b48 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -44,6 +44,9 @@ #define X_DIAG_PIN PB10 // X- #define Y_DIAG_PIN PE12 // Y- #define Z_DIAG_PIN PG8 // Z- +#define E0_DIAG_PIN PE15 // E0 +#define E1_DIAG_PIN PE10 // E1 +#define E2_DIAG_PIN PG5 // E2 // // Limit Switches From 4edaffebfbcb4b3f98277b7b074459a33f7ae622 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 16 Apr 2020 00:03:23 +0000 Subject: [PATCH 0157/1454] [cron] Bump distribution date (2020-04-16) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4bfe64299c..83d5c7e73e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-15" + #define STRING_DISTRIBUTION_DATE "2020-04-16" #endif /** From 808f6329970a3ae4794b7117f1add14c35c65a05 Mon Sep 17 00:00:00 2001 From: randellhodges Date: Wed, 15 Apr 2020 23:12:09 -0500 Subject: [PATCH 0158/1454] Update print job timer with Chamber temp (#17552) --- Marlin/src/gcode/temp/M140_M190.cpp | 20 +++++++++++--------- Marlin/src/gcode/temp/M141_M191.cpp | 13 ++++++++++++- 2 files changed, 23 insertions(+), 10 deletions(-) diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 2da438707b..b0739a8692 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -50,16 +50,18 @@ */ void GcodeSuite::M140() { if (DEBUGGING(DRYRUN)) return; - if (parser.seenval('S')) thermalManager.setTargetBed(parser.value_celsius()); + if (parser.seenval('S')) { + thermalManager.setTargetBed(parser.value_celsius()); - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Both hotend and bed target - * temperatures need to be set below mintemp. Order of M140 and M104 - * at the end of the print does not matter. - */ - thermalManager.check_timer_autostart(false, true); - #endif + #if ENABLED(PRINTJOB_TIMER_AUTOSTART) + /** + * Stop the timer at the end of print. Hotend, bed target, and chamber + * temperatures need to be set below mintemp. Order of M140, M104, and M141 + * at the end of the print does not matter. + */ + thermalManager.check_timer_autostart(false, true); + #endif + } } /** diff --git a/Marlin/src/gcode/temp/M141_M191.cpp b/Marlin/src/gcode/temp/M141_M191.cpp index 3f02836476..d76ba56c95 100644 --- a/Marlin/src/gcode/temp/M141_M191.cpp +++ b/Marlin/src/gcode/temp/M141_M191.cpp @@ -51,7 +51,18 @@ */ void GcodeSuite::M141() { if (DEBUGGING(DRYRUN)) return; - if (parser.seenval('S')) thermalManager.setTargetChamber(parser.value_celsius()); + if (parser.seenval('S')) { + thermalManager.setTargetChamber(parser.value_celsius()); + + #if ENABLED(PRINTJOB_TIMER_AUTOSTART) + /** + * Stop the timer at the end of print. Hotend, bed target, and chamber + * temperatures need to be set below mintemp. Order of M140, M104, and M141 + * at the end of the print does not matter. + */ + thermalManager.check_timer_autostart(false, true); + #endif + } } /** From 791873b10d473074c918c00eb3cee41e46d9ee76 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Wed, 15 Apr 2020 22:17:01 -0600 Subject: [PATCH 0159/1454] Fix ExtUI compile errors (#17544) Fixes #16628 --- Marlin/src/core/multi_language.h | 2 +- .../extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp | 8 +++++--- .../ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp | 2 +- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index ce8ce94fdc..e1cd2f308e 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -76,7 +76,7 @@ typedef const char Language_Str[]; #endif #define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG) -#define MSG_CONCAT(A,B) pgm_p_pair_t(GET_TEXT(A),GET_TEXT(B)) +#define GET_LANGUAGE_NAME(INDEX) GET_LANG(LCD_LANGUAGE_##INDEX)::LANGUAGE #define MSG_1_LINE(A) A "\0" "\0" #define MSG_2_LINE(A,B) A "\0" B "\0" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp index 70acc09071..5ddc4b650c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp @@ -55,9 +55,11 @@ void AboutScreen::onRedraw(draw_mode_t) { #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h #define INSET_POS(pos) _INSET_POS(pos) - char about_str[ - strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + - strlen_P(TOOLHEAD_NAME) + 1 + char about_str[1 + + strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + #ifdef TOOLHEAD_NAME + + strlen_P(TOOLHEAD_NAME) + #endif ]; #ifdef TOOLHEAD_NAME // If MSG_ABOUT_TOUCH_PANEL_2 has %s, substitute in the toolhead name. diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 57137c5d4a..c5f69504d4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -136,7 +136,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #if DISABLED(CLASSIC_JERK) MSG_JUNCTION_DEVIATION #else - JERK_POS + MSG_JERK #endif )) .enabled( From e990a9840416feb002e289bd5f69459439edfc27 Mon Sep 17 00:00:00 2001 From: George Fu Date: Thu, 16 Apr 2020 12:34:48 +0800 Subject: [PATCH 0160/1454] FYSETC TFT81050 LCD support (#17568) --- Marlin/Configuration_adv.h | 1 + .../ftdi_eve_lib/basic/boards.h | 169 +++++++++--------- 2 files changed, 87 insertions(+), 83 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fbfe63036e..616374d5e2 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1344,6 +1344,7 @@ //#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" (480x272) //#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480) //#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI + //#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480) // Correct the resolution if not using the stock TFT panel. //#define TOUCH_UI_320x240 diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h index 854b8897b3..a60cc7d500 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h @@ -25,24 +25,23 @@ #define HAS_RESOLUTION (defined(TOUCH_UI_320x240) || defined(TOUCH_UI_480x272) || defined(TOUCH_UI_800x480)) #define IS_FT800 \ - constexpr uint16_t ftdi_chip = 800; \ - using namespace FTDI_FT800; \ - namespace DL { \ - using namespace FTDI_FT800_DL; \ - } \ - typedef ft800_memory_map ftdi_memory_map; \ - typedef ft800_registers ftdi_registers; + constexpr uint16_t ftdi_chip = 800; \ + using namespace FTDI_FT800; \ + namespace DL { \ + using namespace FTDI_FT800_DL; \ + } \ + typedef ft800_memory_map ftdi_memory_map; \ + typedef ft800_registers ftdi_registers; #define IS_FT810 \ - constexpr uint16_t ftdi_chip = 810; \ - using namespace FTDI_FT810; \ - namespace DL { \ - using namespace FTDI_FT800_DL; \ - using namespace FTDI_FT810_DL; \ - } \ - typedef ft810_memory_map ftdi_memory_map; \ - typedef ft810_registers ftdi_registers; - + constexpr uint16_t ftdi_chip = 810; \ + using namespace FTDI_FT810; \ + namespace DL { \ + using namespace FTDI_FT800_DL; \ + using namespace FTDI_FT810_DL; \ + } \ + typedef ft810_memory_map ftdi_memory_map; \ + typedef ft810_registers ftdi_registers; #ifdef LCD_FTDI_VM800B35A #if !HAS_RESOLUTION @@ -53,30 +52,25 @@ #endif namespace FTDI { IS_FT800 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; /* 1 = does use GPIO00 for amplifier control, 0 = not in use for Audio */ - constexpr bool GPIO_1_Audio_Shutdown = true; /* 1 = does use GPIO01 for amplifier control, 0 = not in use for Audio */ - constexpr uint8_t Swizzle = 2; - constexpr uint8_t CSpread = 1; + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; /* 1 = does use GPIO00 for amplifier control, 0 = not in use for Audio */ + constexpr bool GPIO_1_Audio_Shutdown = true; /* 1 = does use GPIO01 for amplifier control, 0 = not in use for Audio */ + constexpr uint8_t Swizzle = 2; + constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ + constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ } -/* - * Settings for the Haoyu Electronics, 4.3" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY43B) - * Haoyu Electronics, 5" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY50B) - * - * http://www.hotmcu.com/43-graphical-lcd-touchscreen-480x272-spi-ft800-p-111.html?cPath=6_16 - * http://www.hotmcu.com/5-graphical-lcd-touchscreen-480x272-spi-ft800-p-124.html?cPath=6_16 - * +/** + * Settings for the Haoyu Electronics, 4.3" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY43B) + * and 5" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY50B) + * http://www.hotmcu.com/43-graphical-lcd-touchscreen-480x272-spi-ft800-p-111.html?cPath=6_16 + * http://www.hotmcu.com/5-graphical-lcd-touchscreen-480x272-spi-ft800-p-124.html?cPath=6_16 * Datasheet: - * - * http://www.hantronix.com/files/data/1278363262430-3.pdf - * http://www.haoyuelectronics.com/Attachment/HY43-LCD/LCD%20DataSheet.pdf - * http://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf - * + * http://www.hantronix.com/files/data/1278363262430-3.pdf + * http://www.haoyuelectronics.com/Attachment/HY43-LCD/LCD%20DataSheet.pdf + * http://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf */ - #elif defined(LCD_HAOYU_FT800CB) #if !HAS_RESOLUTION #define TOUCH_UI_480x272 @@ -86,25 +80,20 @@ #endif namespace FTDI { IS_FT800 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ } -/* +/** * Settings for the Haoyu Electronics, 5" Graphical LCD Touchscreen, 800x480, SPI, FT810 - * - * http://www.hotmcu.com/5-graphical-lcd-touchscreen-800x480-spi-ft810-p-286.html - * + * http://www.hotmcu.com/5-graphical-lcd-touchscreen-800x480-spi-ft810-p-286.html * Datasheet: - * - * http://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf - * + * http://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf */ - #elif defined(LCD_HAOYU_FT810CB) #if !HAS_RESOLUTION #define TOUCH_UI_800x480 @@ -114,25 +103,20 @@ #endif namespace FTDI { IS_FT810 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ } -/* +/** * Settings for the 4D Systems, 4.3" Embedded SPI Display 480x272, SPI, FT800 (4DLCD-FT843) - * - * http://www.4dsystems.com.au/product/4DLCD_FT843/ - * + * http://www.4dsystems.com.au/product/4DLCD_FT843/ * Datasheet: - * - * http://www.4dsystems.com.au/productpages/4DLCD-FT843/downloads/FT843-4.3-Display_datasheet_R_1_2.pdf - * + * http://www.4dsystems.com.au/productpages/4DLCD-FT843/downloads/FT843-4.3-Display_datasheet_R_1_2.pdf */ - #elif defined(LCD_4DSYSTEMS_4DLCD_FT843) #if !HAS_RESOLUTION #define TOUCH_UI_480x272 @@ -142,23 +126,19 @@ #endif namespace FTDI { IS_FT800 - constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = false; - constexpr bool GPIO_1_Audio_Shutdown = true; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 1; - constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ + constexpr bool Use_Crystal = true; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = false; + constexpr bool GPIO_1_Audio_Shutdown = true; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 1; + constexpr uint16_t touch_threshold = 1200; /* touch-sensitivity */ } -/* +/** * Settings for the Aleph Objects Color LCD User Interface - * - * https://code.alephobjects.com/source/aotctl/ - * + * https://code.alephobjects.com/source/aotctl/ * Datasheet: - * - * http://www.hantronix.com/files/data/s1501799605s500-gh7.pdf - * + * http://www.hantronix.com/files/data/s1501799605s500-gh7.pdf */ #elif defined(LCD_ALEPHOBJECTS_CLCD_UI) #if !HAS_RESOLUTION @@ -169,15 +149,38 @@ #endif namespace FTDI { IS_FT810 - constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated - constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio - constexpr bool GPIO_1_Audio_Shutdown = false; - constexpr uint8_t Swizzle = 0; - constexpr uint8_t CSpread = 0; - constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 0; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ } +/** + * FYSETC Color LCD + * https://www.aliexpress.com/item/4000627651757.html + * Product information: + * https://github.com/FYSETC/TFT81050 + */ +#elif defined(LCD_FYSETC_TFT81050) + #if !HAS_RESOLUTION + #define TOUCH_UI_800x480 + #endif + #ifndef FTDI_API_LEVEL + #define FTDI_API_LEVEL 810 + #endif + namespace FTDI { + IS_FT810 + constexpr bool Use_Crystal = false; // 0 = use internal oscillator, 1 = module has a crystal populated + constexpr bool GPIO_0_Audio_Enable = true; // The AO CLCD uses GPIO0 to enable audio + constexpr bool GPIO_1_Audio_Shutdown = false; + constexpr uint8_t Swizzle = 0; + constexpr uint8_t CSpread = 0; + constexpr uint16_t touch_threshold = 2000; /* touch-sensitivity */ + } #else - #error "Unknown or no TOUCH_UI_FTDI_EVE board specified. To add a new board, modify 'ftdi_eve_boards.h'." + #error "Unknown or no TOUCH_UI_FTDI_EVE board specified. To add a new board, modify this file." + #endif From 089a0af119e81d270435d9ac25c6f6201862d6d3 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 15 Apr 2020 22:04:53 -0700 Subject: [PATCH 0161/1454] More info on E3D, Keenovo, and Wanhao thermistors (#17561) --- Marlin/Configuration.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index b0a0f8ebb8..a4a91078ef 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -364,7 +364,7 @@ * 202 : 200k thermistor - Copymaster 3D * 3 : Mendel-parts thermistor (4.7k pullup) * 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! - * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup) + * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan, J-Head, and E3D) (4.7k pullup) * 501 : 100K Zonestar (Tronxy X3A) Thermistor * 512 : 100k RPW-Ultra hotend thermistor (4.7k pullup) * 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) @@ -373,7 +373,7 @@ * 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) * 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) * 10 : 100k RS thermistor 198-961 (4.7k pullup) - * 11 : 100k beta 3950 1% thermistor (4.7k pullup) + * 11 : 100k beta 3950 1% thermistor (Used in Keenovo AC silicone mats and most Wanhao i3 machines) (4.7k pullup) * 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed) * 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE" * 15 : 100k thermistor calibration for JGAurora A5 hotend @@ -395,7 +395,7 @@ * 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup) * 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) * - * 1047 : Pt1000 with 4k7 pullup + * 1047 : Pt1000 with 4k7 pullup (E3D) * 1010 : Pt1000 with 1k pullup (non standard) * 147 : Pt100 with 4k7 pullup * 110 : Pt100 with 1k pullup (non standard) From 2824e67d95a115ae8bde00608c5768cfd4cccd5f Mon Sep 17 00:00:00 2001 From: Desuuuu Date: Thu, 16 Apr 2020 07:33:31 +0200 Subject: [PATCH 0162/1454] Add ExtUI::onStatusChanged_P (#17543) --- Marlin/src/feature/pause.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 6 ++++++ Marlin/src/lcd/extui/ui_api.h | 1 + 3 files changed, 8 insertions(+), 1 deletion(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 259b130822..657f427656 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -536,7 +536,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING)); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onStatusChanged(GET_TEXT(MSG_REHEATING)); + ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING)); #endif // Re-enable the heaters if they timed out diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index d57adadfef..ddb9cfc3bb 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1071,6 +1071,12 @@ namespace ExtUI { onUserConfirmRequired(msg); } + void onStatusChanged_P(PGM_P const pstr) { + char msg[strlen_P(pstr) + 1]; + strcpy_P(msg, pstr); + onStatusChanged(msg); + } + FileList::FileList() { refresh(); } void FileList::refresh() { num_files = 0xFFFF; } diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 2ed602c32c..3852686898 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -339,6 +339,7 @@ namespace ExtUI { void onUserConfirmRequired(const char * const msg); void onUserConfirmRequired_P(PGM_P const pstr); void onStatusChanged(const char * const msg); + void onStatusChanged_P(PGM_P const pstr); void onFactoryReset(); void onStoreSettings(char *); void onLoadSettings(const char *); From bc856fd8ec5a157e1d58b5afee25418a8fa0a0fb Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Thu, 16 Apr 2020 14:19:24 +0800 Subject: [PATCH 0163/1454] MKS Robin E3 / E3D support (#17569) Co-authored-by: Scott Lahteine --- Marlin/src/core/boards.h | 2 + Marlin/src/pins/pins.h | 4 + Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h | 178 +++++++++++++++ Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h | 205 ++++++++++++++++++ .../PlatformIO/ldscripts/mks_robin_e3.ld | 14 ++ .../share/PlatformIO/scripts/mks_robin_e3.py | 40 ++++ platformio.ini | 17 ++ 7 files changed, 460 insertions(+) create mode 100644 Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h create mode 100644 Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h create mode 100644 buildroot/share/PlatformIO/ldscripts/mks_robin_e3.ld create mode 100644 buildroot/share/PlatformIO/scripts/mks_robin_e3.py diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index c650d7ec75..132699b2d4 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -298,6 +298,8 @@ #define BOARD_GTM32_MINI 4021 // STM32F103VET6 controller #define BOARD_GTM32_MINI_A30 4022 // STM32F103VET6 controller #define BOARD_GTM32_REV_B 4023 // STM32F103VET6 controller +#define BOARD_MKS_ROBIN_E3D 4024 // MKS Robin E3D(STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3 4025 // MKS Robin E3(STM32F103RCT6) // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a1095e23e2..9b32d73851 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -516,6 +516,10 @@ #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 #elif MB(MKS_ROBIN_PRO) #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro +#elif MB(MKS_ROBIN_E3D) + #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 +#elif MB(MKS_ROBIN_E3) + #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 // // ARM Cortex-M4F diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h new file mode 100644 index 0000000000..34c265c47b --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h @@ -0,0 +1,178 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * MKS Robin E3D (STM32F103RCT6) board pin assignments + */ + +#ifndef __STM32F1__ + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3D supports up to 1 hotends / E-steppers. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "MKS Robin E3D" +#endif +#define BOARD_WEBSITE_URL "github.com/makerbase-mks" + +//#define DISABLE_DEBUG +#define DISABLE_JTAG +#define ENABLE_SPI2 + +// +// Servos +// +#define SERVO0_PIN PA3 + +// +// Limit Switches +// +#define X_STOP_PIN PA12 +#define Y_STOP_PIN PA11 +#define Z_MIN_PIN PC6 +#define Z_MAX_PIN PB1 + +// +// Steppers +// +#define X_STEP_PIN PC0 +#define X_DIR_PIN PB2 +#define X_ENABLE_PIN PC13 + +#define Y_STEP_PIN PC2 +#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PB12 + +#define Z_STEP_PIN PB7 +#define Z_DIR_PIN PB6 +#define Z_ENABLE_PIN PB8 + +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB3 +#define E0_ENABLE_PIN PB5 + +#if HAS_TMC220x + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PC7 + #define X_SERIAL_RX_PIN PC7 + + #define Y_SERIAL_TX_PIN PD2 + #define Y_SERIAL_RX_PIN PD2 + + #define Z_SERIAL_TX_PIN PC12 + #define Z_SERIAL_RX_PIN PC12 + + #define E0_SERIAL_TX_PIN PC11 + #define E0_SERIAL_RX_PIN PC11 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Heaters 0,1 / Fans / Bed +// +#define HEATER_0_PIN PC9 +#define FAN_PIN PA8 +#define HEATER_BED_PIN PC8 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PA1 //TB +#define TEMP_0_PIN PA0 //TH1 + +#define FIL_RUNOUT_PIN PB10 // MT_DET + +// +// LCD Pins +// +#if HAS_SPI_LCD + + #define BEEPER_PIN PC1 + #define BTN_ENC PC3 + #define LCD_PINS_ENABLE PA4 + #define LCD_PINS_RS PA5 + #define BTN_EN1 PB11 + #define BTN_EN2 PB0 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 PC4 + #define DOGLCD_CS PA7 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 + + // Required for MKS_MINI_12864 with this board + #define MKS_LCD12864B + #undef SHOW_BOOTSCREEN + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 PA6 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PA7 + #define LCD_PINS_D6 PC4 + #define LCD_PINS_D7 PC5 + #endif + + #endif // !MKS_MINI_12864 + +#endif // HAS_SPI_LCD + +// +// SD Card +// +#define ENABLE_SPI2 +#define SD_DETECT_PIN PC10 +#define SCK_PIN PB13 +#define MISO_PIN PB14 +#define MOSI_PIN PB15 +#define SS_PIN PA15 + +#ifndef ST7920_DELAY_1 + #define ST7920_DELAY_1 DELAY_NS(125) +#endif +#ifndef ST7920_DELAY_2 + #define ST7920_DELAY_2 DELAY_NS(125) +#endif +#ifndef ST7920_DELAY_3 + #define ST7920_DELAY_3 DELAY_NS(125) +#endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h new file mode 100644 index 0000000000..9091c99dfc --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -0,0 +1,205 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * MKS Robin E3D (STM32F103RCT6) board pin assignments + */ + +#ifndef __STM32F1__ + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3D supports up to 1 hotends / E-steppers. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "MKS Robin E3D" +#endif +#define BOARD_WEBSITE_URL "github.com/makerbase-mks" + +//#define DISABLE_DEBUG +#define DISABLE_JTAG +#define ENABLE_SPI2 + +// +// Servos +// +#define SERVO0_PIN PA3 + +// +// Limit Switches +// +#define X_STOP_PIN PA12 +#define Y_STOP_PIN PA11 +#define Z_MIN_PIN PC6 +#define Z_MAX_PIN PB1 + +// +// Steppers +// +#define X_STEP_PIN PC0 +#define X_DIR_PIN PB2 +#define X_ENABLE_PIN PC13 +#ifndef X_CS_PIN + #define X_CS_PIN PC7 +#endif + +#define Y_STEP_PIN PC2 +#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PB12 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD2 +#endif + +#define Z_STEP_PIN PB7 +#define Z_DIR_PIN PB6 +#define Z_ENABLE_PIN PB8 +#ifndef Z_CS_PIN + #define Z_CS_PIN PC12 +#endif + +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB3 +#define E0_ENABLE_PIN PB5 +#ifndef E0_CS_PIN + #define E0_CS_PIN PC11 +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PB15 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PB14 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PB13 + #endif +#endif + +#if HAS_TMC220x + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PC7 + #define X_SERIAL_RX_PIN PC7 + + #define Y_SERIAL_TX_PIN PD2 + #define Y_SERIAL_RX_PIN PD2 + + #define Z_SERIAL_TX_PIN PC12 + #define Z_SERIAL_RX_PIN PC12 + + #define E0_SERIAL_TX_PIN PC11 + #define E0_SERIAL_RX_PIN PC11 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Heaters 0,1 / Fans / Bed +// +#define HEATER_0_PIN PC9 +#define FAN_PIN PA8 +#define HEATER_BED_PIN PC8 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PA1 //TB +#define TEMP_0_PIN PA0 //TH1 + +#define FIL_RUNOUT_PIN PB10 // MT_DET + +// +// LCD Pins +// +#if HAS_SPI_LCD + + #define BEEPER_PIN PC1 + #define BTN_ENC PC3 + #define LCD_PINS_ENABLE PA4 + #define LCD_PINS_RS PA5 + #define BTN_EN1 PB11 + #define BTN_EN2 PB0 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 PC4 + #define DOGLCD_CS PA7 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 + + // Required for MKS_MINI_12864 with this board + #define MKS_LCD12864B + #undef SHOW_BOOTSCREEN + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 PA6 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PA7 + #define LCD_PINS_D6 PC4 + #define LCD_PINS_D7 PC5 + #endif + + #endif // !MKS_MINI_12864 + +#endif // HAS_SPI_LCD + +// +// SD Card +// +#define ENABLE_SPI2 +#define SD_DETECT_PIN PC10 +#define SCK_PIN PB13 +#define MISO_PIN PB14 +#define MOSI_PIN PB15 +#define SS_PIN PA15 + +#ifndef ST7920_DELAY_1 + #define ST7920_DELAY_1 DELAY_NS(125) +#endif +#ifndef ST7920_DELAY_2 + #define ST7920_DELAY_2 DELAY_NS(125) +#endif +#ifndef ST7920_DELAY_3 + #define ST7920_DELAY_3 DELAY_NS(125) +#endif diff --git a/buildroot/share/PlatformIO/ldscripts/mks_robin_e3.ld b/buildroot/share/PlatformIO/ldscripts/mks_robin_e3.ld new file mode 100644 index 0000000000..13fa48add4 --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/mks_robin_e3.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08005000, LENGTH = 256K - 20K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py new file mode 100644 index 0000000000..3af623cce0 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py @@ -0,0 +1,40 @@ +import os +Import("env") + +# Relocate firmware from 0x08000000 to 0x08005000 +for define in env['CPPDEFINES']: + if define[0] == "VECT_TAB_ADDR": + env['CPPDEFINES'].remove(define) +env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08005000")) + +custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/mks_robin_e3.ld") +for i, flag in enumerate(env["LINKFLAGS"]): + if "-Wl,-T" in flag: + env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script + elif flag == "-T": + env["LINKFLAGS"][i + 1] = custom_ld_script + + +# Encrypt ${PROGNAME}.bin and save it as 'mksLite.bin' +def encrypt(source, target, env): + import sys + + key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] + + firmware = open(target[0].path, "rb") + robin = open(target[0].dir.path +'/Robin_e3.bin', "wb") + length = os.path.getsize(target[0].path) + position = 0 + try: + while position < length: + byte = firmware.read(1) + if position >= 320 and position < 31040: + byte = chr(ord(byte) ^ key[position & 31]) + if sys.version_info[0] > 2: + byte = bytes(byte, 'latin1') + robin.write(byte) + position += 1 + finally: + firmware.close() + robin.close() +env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); diff --git a/platformio.ini b/platformio.ini index 38e3065f20..63df14cf63 100644 --- a/platformio.ini +++ b/platformio.ini @@ -543,6 +543,23 @@ src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} lib_ignore = Adafruit NeoPixel, SPI, TMCStepper +# +# MKS Robin E3D (STM32F103RCT6) and +# MKS Robin E3 with TMC2209 +# +[env:mks_robin_e3] +platform = ststm32 +board = genericSTM32F103RC +platform_packages = tool-stm32duino +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py + ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 +build_unflags = -std=gnu++11 +extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_e3.py +src_filter = ${common.default_src_filter} + +lib_deps = ${common.lib_deps} + SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +lib_ignore = Adafruit NeoPixel, SPI + # # MKS Robin Lite/Lite2 (STM32F103RCT6) # From 880f63b008d13f0df89ebe62e6c11193748ae828 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Apr 2020 01:56:37 -0500 Subject: [PATCH 0164/1454] It looks like HAS_ONBOARD_SD is obsolete --- Marlin/src/HAL/STM32F1/msc_sd.cpp | 4 ++-- Marlin/src/HAL/STM32F1/onboard_sd.cpp | 6 +++--- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 2 -- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 2 -- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 3 +-- 6 files changed, 7 insertions(+), 12 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index a086b82bc3..aca0268440 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -25,7 +25,7 @@ USBCompositeSerial MarlinCompositeSerial; #include "../../inc/MarlinConfig.h" -#ifdef HAS_ONBOARD_SD +#if SD_CONNECTION_IS(ONBOARD) #include "onboard_sd.h" @@ -47,7 +47,7 @@ void MSC_SD_init() { USBComposite.end(); USBComposite.clear(); // Set api and register mass storage - #ifdef HAS_ONBOARD_SD + #if SD_CONNECTION_IS(ONBOARD) uint32_t cardSize; if (disk_initialize(0) == RES_OK) { if (disk_ioctl(0, GET_SECTOR_COUNT, (void *)(&cardSize)) == RES_OK) { diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index 0fd94a9199..f1fbdc08d8 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -14,13 +14,13 @@ #include "../../inc/MarlinConfig.h" -#ifdef HAS_ONBOARD_SD +#if SD_CONNECTION_IS(ONBOARD) #include "onboard_sd.h" #include "SPI.h" #include "fastio.h" -#ifdef SHARED_SD_CARD +#if ENABLED(SHARED_SD_CARD) #ifndef ON_BOARD_SPI_DEVICE #define ON_BOARD_SPI_DEVICE SPI_DEVICE #endif @@ -553,4 +553,4 @@ DRESULT disk_read ( #endif // _DISKIO_IOCTL -#endif // HAS_ONBOARD_SD +#endif // SD_CONNECTION_IS(ONBOARD) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index b38aaa1332..b28b27792d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -339,7 +339,7 @@ #endif #if DISABLED(SHARED_SD_CARD) - #define INIT_SDCARD_ON_BOOT 1 + #define INIT_SDCARD_ON_BOOT #endif #if PIN_EXISTS(SD_DETECT) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index fef8eeb617..89e184524c 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -223,8 +223,6 @@ // // SD Support // -#define HAS_ONBOARD_SD - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 15bc01263a..d7a72592ef 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -181,8 +181,6 @@ // // SD Support // -#define HAS_ONBOARD_SD - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index fff3af5b6b..8d2d18566d 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -179,8 +179,7 @@ // // By default the onboard SD is enabled. -// set SDCARD_CONNECTION form 'ONBOARD' to 'LCD' and use an external SD (connected to LCD) -#define HAS_ONBOARD_SD +// Change SDCARD_CONNECTION from 'ONBOARD' to 'LCD' for an external (LCD module) SD #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif From 3a9f8a00bf7fcfa0cd6142c334d7b699ca475cb8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Apr 2020 01:57:07 -0500 Subject: [PATCH 0165/1454] Fix SD connection for some boards --- Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h | 2 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 2 +- Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index 170b90368b..f9b548420d 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -142,7 +142,7 @@ #define SDIO_CK_PIN PC12 #define SDIO_CMD_PIN PD2 -#if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD +#if !defined(SDCARD_CONNECTION) || SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 8205cd9f4d..ffae5cc0ef 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -164,7 +164,7 @@ #define SDIO_CK_PIN PC12 #define SDIO_CMD_PIN PD2 -#if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD +#if !defined(SDCARD_CONNECTION) || SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 1a008cd4ae..fcac3da30c 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -239,7 +239,7 @@ #define SDCARD_CONNECTION ONBOARD #endif -#if SDCARD_CONNECTION == ONBOARD +#if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT From 03020dd31ec3ae05135d074f4e9c07f8482f5ea0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Apr 2020 03:24:41 -0500 Subject: [PATCH 0166/1454] Use the common pattern for auto fan pins Now that pins.h is guaranteed included after configs. --- Marlin/Configuration_adv.h | 2 + Marlin/src/inc/SanityCheck.h | 4 ++ .../src/pins/lpc1769/pins_COHESION3D_MINI.h | 13 ++-- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 12 +++- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 12 +++- Marlin/src/pins/mega/pins_CNCONTROLS_11.h | 20 ++++-- Marlin/src/pins/mega/pins_CNCONTROLS_12.h | 20 ++++-- Marlin/src/pins/mega/pins_CNCONTROLS_15.h | 25 +++++-- Marlin/src/pins/mega/pins_SILVER_GATE.h | 5 +- Marlin/src/pins/pins.h | 67 ------------------- Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h | 21 ++++-- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 16 +++-- Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h | 4 +- Marlin/src/pins/ramps/pins_TANGO.h | 4 +- Marlin/src/pins/ramps/pins_TRIGORILLA_13.h | 9 ++- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 5 +- Marlin/src/pins/ramps/pins_ULTIMAIN_2.h | 4 +- Marlin/src/pins/ramps/pins_VORON.h | 12 +++- Marlin/src/pins/ramps/pins_ZRIB_V20.h | 19 ++++-- Marlin/src/pins/sam/pins_CNCONTROLS_15D.h | 25 +++++-- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 2 - Marlin/src/pins/sensitive_pins.h | 25 +++++++ Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 5 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 5 +- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 5 +- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 5 +- .../src/pins/stm32f4/pins_GENERIC_STM32F4.h | 4 +- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 4 +- Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 6 +- .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 5 +- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 4 +- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 4 +- Marlin/src/pins/stm32f7/pins_THE_BORG.h | 4 +- 33 files changed, 245 insertions(+), 132 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 616374d5e2..91646d8854 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -425,6 +425,8 @@ #define E3_AUTO_FAN_PIN -1 #define E4_AUTO_FAN_PIN -1 #define E5_AUTO_FAN_PIN -1 +#define E6_AUTO_FAN_PIN -1 +#define E7_AUTO_FAN_PIN -1 #define CHAMBER_AUTO_FAN_PIN -1 #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 185f5c0b4d..bc41e4612f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -489,6 +489,10 @@ #error "Z_QUAD_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h." #elif defined(DUGS_UI_MOVE_DIS_OPTION) #error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION. Please update Configuration_adv.h." +#elif defined(ORIG_E0_AUTO_FAN_PIN) || defined(ORIG_E1_AUTO_FAN_PIN) || defined(ORIG_E2_AUTO_FAN_PIN) || defined(ORIG_E3_AUTO_FAN_PIN) || defined(ORIG_E4_AUTO_FAN_PIN) || defined(ORIG_E5_AUTO_FAN_PIN) || defined(ORIG_E6_AUTO_FAN_PIN) || defined(ORIG_E7_AUTO_FAN_PIN) + #error "ORIG_Ex_AUTO_FAN_PIN is now just Ex_AUTO_FAN_PIN. Make sure your pins are up to date." +#elif defined(ORIG_CHAMBER_AUTO_FAN_PIN) + #error "ORIG_CHAMBER_AUTO_FAN_PIN is now just CHAMBER_AUTO_FAN_PIN. Make sure your pins are up to date." #endif /** diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index 87d3cb459c..f696d060db 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -110,10 +110,15 @@ // Auto fans // #define AUTO_FAN_PIN P2_04 // FET 4 - -#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif // // Misc. Functions diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index fa55a8adae..179909a4ce 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -139,9 +139,15 @@ #else #define AUTO_FAN_PIN P1_22 // FET 3 #endif -#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif // // Misc. Functions diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index d4030ed790..d4e87e24dd 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -131,9 +131,15 @@ // Auto fans // #define AUTO_FAN_PIN P1_22 // FET 3 -#define ORIG_E0_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E1_AUTO_FAN_PIN AUTO_FAN_PIN -#define ORIG_E2_AUTO_FAN_PIN AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif // // SD Card diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index 833499fe0f..5db94b3d96 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -95,10 +95,22 @@ //#define FAN_PIN 7 // common PWM pin for all tools #endif -#define ORIG_E0_AUTO_FAN_PIN 7 -#define ORIG_E1_AUTO_FAN_PIN 7 -#define ORIG_E2_AUTO_FAN_PIN 7 -#define ORIG_E3_AUTO_FAN_PIN 7 +// +// Auto fans +// +#define AUTO_FAN_PIN 7 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN AUTO_FAN_PIN +#endif // // Misc. Functions diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 680a5c9a99..b021df109a 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -95,10 +95,22 @@ #define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools #endif -#define ORIG_E0_AUTO_FAN_PIN 7 -#define ORIG_E1_AUTO_FAN_PIN 7 -#define ORIG_E2_AUTO_FAN_PIN 7 -#define ORIG_E3_AUTO_FAN_PIN 7 +// +// Auto fans +// +#define AUTO_FAN_PIN 7 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN AUTO_FAN_PIN +#endif // // Misc. Functions diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index b4aa8ab815..29ec8e938e 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -88,11 +88,26 @@ // Fans // #define FAN_PIN 8 -#define ORIG_E0_AUTO_FAN_PIN 30 -#define ORIG_E1_AUTO_FAN_PIN 30 -#define ORIG_E2_AUTO_FAN_PIN 30 -#define ORIG_E3_AUTO_FAN_PIN 30 -//#define ORIG_CHAMBER_AUTO_FAN_PIN 10 + +// +// Auto fans +// +#define AUTO_FAN_PIN 30 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef CHAMBER_AUTO_FAN_PIN + //#define CHAMBER_AUTO_FAN_PIN 10 +#endif // // Misc. Functions diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 4c79507eab..351691a09e 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -61,7 +61,10 @@ #define HEATER_0_PIN 7 -#define ORIG_E0_AUTO_FAN_PIN 3 // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 3 +#endif + #define CONTROLLER_FAN_PIN 2 #define TEMP_0_PIN 7 // Analog Input diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 9b32d73851..86cfd0b535 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -1051,73 +1051,6 @@ #define NUM_SERVO_PLUGS 4 #endif -// -// Assign auto fan pins if needed -// -#ifndef E0_AUTO_FAN_PIN - #ifdef ORIG_E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN ORIG_E0_AUTO_FAN_PIN - #else - #define E0_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E1_AUTO_FAN_PIN - #ifdef ORIG_E1_AUTO_FAN_PIN - #define E1_AUTO_FAN_PIN ORIG_E1_AUTO_FAN_PIN - #else - #define E1_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E2_AUTO_FAN_PIN - #ifdef ORIG_E2_AUTO_FAN_PIN - #define E2_AUTO_FAN_PIN ORIG_E2_AUTO_FAN_PIN - #else - #define E2_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E3_AUTO_FAN_PIN - #ifdef ORIG_E3_AUTO_FAN_PIN - #define E3_AUTO_FAN_PIN ORIG_E3_AUTO_FAN_PIN - #else - #define E3_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E4_AUTO_FAN_PIN - #ifdef ORIG_E4_AUTO_FAN_PIN - #define E4_AUTO_FAN_PIN ORIG_E4_AUTO_FAN_PIN - #else - #define E4_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E5_AUTO_FAN_PIN - #ifdef ORIG_E5_AUTO_FAN_PIN - #define E5_AUTO_FAN_PIN ORIG_E5_AUTO_FAN_PIN - #else - #define E5_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E6_AUTO_FAN_PIN - #ifdef ORIG_E6_AUTO_FAN_PIN - #define E6_AUTO_FAN_PIN ORIG_E6_AUTO_FAN_PIN - #else - #define E6_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef E7_AUTO_FAN_PIN - #ifdef ORIG_E7_AUTO_FAN_PIN - #define E7_AUTO_FAN_PIN ORIG_E7_AUTO_FAN_PIN - #else - #define E7_AUTO_FAN_PIN -1 - #endif -#endif -#ifndef CHAMBER_AUTO_FAN_PIN - #ifdef ORIG_CHAMBER_AUTO_FAN_PIN - #define CHAMBER_AUTO_FAN_PIN ORIG_CHAMBER_AUTO_FAN_PIN - #else - #define CHAMBER_AUTO_FAN_PIN -1 - #endif -#endif - // // Assign endstop pins for boards with only 3 connectors // diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index c8e2a6683d..7605f10b67 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -118,11 +118,22 @@ #define CONTROLLER_FAN_PIN 4 // Pin used for the fan to cool motherboard (-1 to disable) #endif -// Fans/Water Pump to cool the hotend cool side. -#define ORIG_E0_AUTO_FAN_PIN 5 -#define ORIG_E1_AUTO_FAN_PIN 5 -#define ORIG_E2_AUTO_FAN_PIN 5 -#define ORIG_E3_AUTO_FAN_PIN 5 +// +// Auto fans +// +#define AUTO_FAN_PIN 5 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN AUTO_FAN_PIN +#endif // // LCD / Controller diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 44b6ff1e61..454311b7cc 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -42,10 +42,18 @@ // // Auto fans // -#define ORIG_E0_AUTO_FAN_PIN 11 -#define ORIG_E1_AUTO_FAN_PIN 6 -#define ORIG_E2_AUTO_FAN_PIN 6 -#define ORIG_E3_AUTO_FAN_PIN 6 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 11 +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN 6 +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN 6 +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN 6 +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h b/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h index b0ba7822ef..f2298d2557 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_DAGOMA.h @@ -32,7 +32,9 @@ #define Z_STOP_PIN 15 #define FIL_RUNOUT_PIN 39 -#define ORIG_E0_AUTO_FAN_PIN 7 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 7 +#endif // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index 221b30b0cb..9be5c04b69 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -30,7 +30,9 @@ #define FAN_PIN 8 #define FAN1_PIN -1 -#define ORIG_E0_AUTO_FAN_PIN 7 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 7 +#endif #ifndef TEMP_0_PIN #if TEMP_SENSOR_0 == -1 diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h index c0b8630354..b29988823d 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h @@ -28,9 +28,12 @@ #define BOARD_INFO_NAME "Anycubic RAMPS 1.3" #define IS_RAMPS_EFB -#define RAMPS_D9_PIN 44 -#define FAN2_PIN 9 -#define ORIG_E0_AUTO_FAN_PIN 9 +#define RAMPS_D9_PIN 44 +#define FAN2_PIN 9 + +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 9 +#endif #include "pins_RAMPS_13.h" diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index f32f006e92..adbacfbf4d 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -83,7 +83,10 @@ #define FAN1_PIN TG_FAN1_PIN #endif #define FAN2_PIN TG_FAN2_PIN -#define ORIG_E0_AUTO_FAN_PIN TG_FAN2_PIN // Used in Anycubic Kossel example config + +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN TG_FAN2_PIN // Used in Anycubic Kossel example config +#endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index 776dfcc3da..b0a3f23249 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -98,7 +98,9 @@ #define FAN_PIN 7 #endif -#define ORIG_E0_AUTO_FAN_PIN 77 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 77 +#endif // // Misc. Functions diff --git a/Marlin/src/pins/ramps/pins_VORON.h b/Marlin/src/pins/ramps/pins_VORON.h index 12c0a36db1..31b273d09e 100644 --- a/Marlin/src/pins/ramps/pins_VORON.h +++ b/Marlin/src/pins/ramps/pins_VORON.h @@ -38,8 +38,16 @@ #undef FAN_PIN #define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. #define CONTROLLER_FAN_PIN 8 -#define ORIG_E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan -#define ORIG_E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) + +// +// Auto fans +// +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) +#endif // // LCDs and Controllers diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V20.h b/Marlin/src/pins/ramps/pins_ZRIB_V20.h index 5aee07c96f..a40800158c 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V20.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V20.h @@ -39,10 +39,21 @@ #define ZRIB_V20_D29_PIN 29 #define ZRIB_V20_D37_PIN 37 -#define ORIG_E0_AUTO_FAN_PIN ZRIB_V20_D6_PIN -#define ORIG_E1_AUTO_FAN_PIN ZRIB_V20_D6_PIN -#define ORIG_E2_AUTO_FAN_PIN ZRIB_V20_D6_PIN -#define ORIG_E3_AUTO_FAN_PIN ZRIB_V20_D6_PIN +// +// Auto fans +// +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN ZRIB_V20_D6_PIN +#endif #ifndef FILWIDTH_PIN #define FILWIDTH_PIN 11 // Analog Input diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index f23d008bec..e1f34bdfe0 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -93,11 +93,26 @@ // Fans // //#define FAN0_PIN 8 -#define ORIG_E0_AUTO_FAN_PIN 30 -#define ORIG_E1_AUTO_FAN_PIN 30 -#define ORIG_E2_AUTO_FAN_PIN 30 -#define ORIG_E3_AUTO_FAN_PIN 30 -#define ORIG_CHAMBER_AUTO_FAN_PIN 10 + +// +// Auto fans +// +#define AUTO_FAN_PIN 30 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef CHAMBER_AUTO_FAN_PIN + #define CHAMBER_AUTO_FAN_PIN 10 +#endif // // SD card diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 3ba6fd17cf..0d06b14936 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -240,8 +240,6 @@ #elif ENABLED(MKS_MINI_12864) - #define ORIG_BEEPER_PIN 62 - #define DOGLCD_A0 52 #define DOGLCD_CS 50 diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 180bc8d6f6..f56a00b82f 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -389,6 +389,31 @@ // Heaters, Fans, Temp Sensors // +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN -1 +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN -1 +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN -1 +#endif +#ifndef E3_AUTO_FAN_PIN + #define E3_AUTO_FAN_PIN -1 +#endif +#ifndef E4_AUTO_FAN_PIN + #define E4_AUTO_FAN_PIN -1 +#endif +#ifndef E5_AUTO_FAN_PIN + #define E5_AUTO_FAN_PIN -1 +#endif +#ifndef E6_AUTO_FAN_PIN + #define E6_AUTO_FAN_PIN -1 +#endif +#ifndef E7_AUTO_FAN_PIN + #define E7_AUTO_FAN_PIN -1 +#endif + #define _H0_PINS #define _H1_PINS #define _H2_PINS diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 38cc615f64..3fd0b5ae46 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -110,10 +110,13 @@ // These are FAN PWM pins on EXT0..EXT2 connectors. // //#define FAN_PIN PB9 // EXT0 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#endif + // // Temperature Sensors // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 873d02b065..9a12cfd7b0 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -110,10 +110,13 @@ // These are FAN PWM pins on EXT0..EXT2 connectors. // //#define FAN_PIN PB9 // EXT0 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#endif + // // Temperature Sensors // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 38cc615f64..3fd0b5ae46 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -110,10 +110,13 @@ // These are FAN PWM pins on EXT0..EXT2 connectors. // //#define FAN_PIN PB9 // EXT0 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#endif + // // Temperature Sensors // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 24196ad892..f885db7fed 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -112,7 +112,10 @@ //#define FAN_PIN PB9 // EXT0 port #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port -#define ORIG_E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan + +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PB9 // EXT0 port, used as main extruder fan +#endif // // Temperature Sensors diff --git a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h index 924b94c4f1..5df7ffe466 100644 --- a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h +++ b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h @@ -126,7 +126,9 @@ #define FAN1_PIN PC7 #define FAN2_PIN PC8 -#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PC7 +#endif // // Misc. Functions diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index d21cdd0958..3d274b1dc4 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -115,7 +115,9 @@ #define FAN1_PIN PF6 #define FAN2_PIN PF7 -#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PF6 +#endif // // LED / Lighting diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index c54c5c1806..436381e4fe 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -107,12 +107,14 @@ #define HEATER_BED_PIN PA2 #ifndef FAN_PIN -// #define FAN_PIN PC15 + //#define FAN_PIN PC15 #endif #define FAN1_PIN PC15 #define FAN2_PIN PA0 -#define ORIG_E0_AUTO_FAN_PIN PC15 // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PC15 // FAN1_PIN +#endif // // Prusa i3 MK2 Multi Material Multiplexer Support diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index fcac3da30c..40b00bcc40 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -166,9 +166,12 @@ #define FAN_PIN 57 // PC4 E1_FAN PWM pin, Part cooling fan FET #define FAN1_PIN 58 // PC5 E2_FAN PWM pin, Extruder fan FET -#define ORIG_E0_AUTO_FAN_PIN FAN1_PIN #define FAN2_PIN 59 // PE8 E3_FAN PWM pin, Controller fan FET +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 58 // FAN1_PIN +#endif + // // Misc functions // diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 7eb95a4f50..4d27910c16 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -135,7 +135,9 @@ #define FAN1_PIN PB5 // PA0 #define FAN2_PIN PB4 // PA1 -#define ORIG_E0_AUTO_FAN_PIN PD13 // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PD13 +#endif // // Misc. Functions diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index 736445cdab..ac337092f6 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -99,7 +99,9 @@ #endif #define FAN1_PIN 32 // "FAN2" -#define ORIG_E0_AUTO_FAN_PIN 32 // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 32 +#endif // // Servos diff --git a/Marlin/src/pins/stm32f7/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h index 9968d9d1f1..c937c53972 100644 --- a/Marlin/src/pins/stm32f7/pins_THE_BORG.h +++ b/Marlin/src/pins/stm32f7/pins_THE_BORG.h @@ -127,7 +127,9 @@ #define FAN1_PIN PA0 #define FAN2_PIN PA1 -#define ORIG_E0_AUTO_FAN_PIN PA1 // Use this by NOT overriding E0_AUTO_FAN_PIN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PA1 +#endif // // Misc. Functions From 1c43870cecb76b67f8c7b0f260f0a685b4591bbf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Apr 2020 03:05:36 -0500 Subject: [PATCH 0167/1454] Add chamber to sensitive pins --- Marlin/src/pins/sensitive_pins.h | 27 +++++++++++++++++++-------- 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index f56a00b82f..12cadcbd9c 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -456,12 +456,6 @@ #endif // HOTENDS > 1 #endif // HOTENDS -#define _BED_PINS -#if PIN_EXISTS(HEATER_BED) && PIN_EXISTS(TEMP_BED) - #undef _BED_PINS - #define _BED_PINS HEATER_BED_PIN, analogInputToDigitalPin(TEMP_BED_PIN), -#endif - // // Dual X, Dual Y, Multi-Z // Chip Select and Digital Micro-stepping @@ -666,14 +660,31 @@ #define _FANC #endif +#if PIN_EXISTS(HEATER_BED) && PIN_EXISTS(TEMP_BED) + #define _BED_PINS HEATER_BED_PIN, analogInputToDigitalPin(TEMP_BED_PIN), +#else + #define _BED_PINS +#endif + +#if PIN_EXISTS(TEMP_CHAMBER) + #define __CHAMBER_PINS CHAMBER_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_CHAMBER_PIN), +#else + #define __CHAMBER_PINS +#endif +#if PIN_EXISTS(HEATER_CHAMBER) + #define _CHAMBER_PINS __CHAMBER_PINS HEATER_CHAMBER_PIN, +#else + #define _CHAMBER_PINS +#endif + #ifndef HAL_SENSITIVE_PINS #define HAL_SENSITIVE_PINS #endif #define SENSITIVE_PINS { \ _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ - _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS _BED_PINS \ + _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \ _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \ _PS_ON _HEATER_BED _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \ - HAL_SENSITIVE_PINS \ + _BED_PINS _CHAMBER_PINS HAL_SENSITIVE_PINS \ } From d8b8d88276c862bea30f86e492fe52712cd4bd16 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Apr 2020 03:36:53 -0500 Subject: [PATCH 0168/1454] Move setup logging to the top --- Marlin/src/MarlinCore.cpp | 31 ++++++++++++++++--------------- 1 file changed, 16 insertions(+), 15 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index d05c9c6014..e4fbf31a27 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -875,6 +875,19 @@ void stop() { */ void setup() { + #if ENABLED(MARLIN_DEV_MODE) + auto log_current_ms = [&](PGM_P const msg) { + SERIAL_ECHO_START(); + SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHO("] "); + serialprintPGM(msg); + SERIAL_EOL(); + }; + #define SETUP_LOG(M) log_current_ms(PSTR(M)) + #else + #define SETUP_LOG(...) NOOP + #endif + #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0) + HAL_init(); #if HAS_L64XX @@ -939,12 +952,13 @@ void setup() { #if HAS_TMC_SPI #if DISABLED(TMC_USE_SW_SPI) - SPI.begin(); + SETUP_RUN(SPI.begin()); #endif - tmc_init_cs_pins(); + SETUP_RUN(tmc_init_cs_pins()); #endif #ifdef BOARD_INIT + SETUP_LOG("BOARD_INIT"); BOARD_INIT(); #endif @@ -977,19 +991,6 @@ void setup() { // UI must be initialized before EEPROM // (because EEPROM code calls the UI). - #if ENABLED(MARLIN_DEV_MODE) - auto log_current_ms = [&](PGM_P const msg) { - SERIAL_ECHO_START(); - SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHO("] "); - serialprintPGM(msg); - SERIAL_EOL(); - }; - #define SETUP_LOG(M) log_current_ms(PSTR(M)) - #else - #define SETUP_LOG(...) NOOP - #endif - #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0) - // Set up LEDs early #if HAS_COLOR_LEDS SETUP_RUN(leds.setup()); From 0ce532547af9beeb3900b03f1cb42ca4ab956efa Mon Sep 17 00:00:00 2001 From: android444 Date: Thu, 16 Apr 2020 10:40:17 +0200 Subject: [PATCH 0169/1454] Update Polish language (#17525) --- Marlin/src/lcd/language/language_pl.h | 44 +++++++++++++-------------- 1 file changed, 22 insertions(+), 22 deletions(-) diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index b8b48bc480..cd3fbe0da9 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -159,7 +159,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Nagrzewanie dyszy"); PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Napełnianie ręczne..."); PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Napełnij kreśloną długością"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Napełianie zakończone"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Napełnianie zakończone"); PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Przewane"); PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Opuszczanie G26"); PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Kontynuuj tworzenie siatki"); @@ -184,17 +184,17 @@ namespace Language_pl { PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Dostrajaj najbliższy"); PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Przechowywanie siatki"); PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot Pamięci"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Załaduj siatke stołu"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Zapisz siatke stołu"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Załaduj siatkę stołu"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Zapisz siatkę stołu"); PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Siatka %i załadowana"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Siatka %i Zapisana"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Siatka %i zapisana"); PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Brak magazynu"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Błąd: Zapis UBL"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Bład: Odczyt UBL"); PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Przesunięcie Z: "); PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Przesunięcie Z zatrzymane"); PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Krok po kroku"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Tworzeni ezimnej siatki"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Tworzenie zimnej siatki"); PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligentne wypełnienie"); PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Sprawdzenie siatki"); PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Dostrojenie wszystkiego"); @@ -291,8 +291,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm³"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Wyładuj mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Załaduj mm"); + PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); + PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Wsuń mm"); PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD"); @@ -345,11 +345,11 @@ namespace Language_pl { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Załaduj Filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Załaduj Filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Wyładuj Filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Wyładuj Filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Wyładuj wszystkie"); + PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); + PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Wsuń Filament *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Wysuń Filament"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Wysuń Filament *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Wysuń wszystkie"); PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Inicjal. karty SD"); PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Zmiana karty SD"); PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); @@ -367,7 +367,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("NIEBEZPIECZNE: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); @@ -465,8 +465,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Zapisz DAC EEPROM"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("ZMIEŃ FILAMENT"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("WYDRUK WSTRZYMANY"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ZAŁADUJ FILAMENT"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("WYŁADUJ FILAMENT"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("WSUŃ FILAMENT"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("WYSUŃ FILAMENT"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCJE WZNOWIENIA:"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Oczyść więcej"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Kontynuuj"); @@ -483,15 +483,15 @@ namespace Language_pl { PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Wznawianie..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Załaduj filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Załaduj wszystko"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Załaduj do dyszy"); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Wsuń filament"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Wsuń wszystko"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Wsuń do dyszy"); PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Wysuń filament"); PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Wysuń filament ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Wyładuj filament"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Ładowanie fil. %i..."); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Wysuń filament"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Wsuwanie fil. %i..."); PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wyładowywanie fil...."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Wszystko"); PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetuj MMU"); @@ -547,7 +547,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknij by nagrzać")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Nagrzewanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Wysuwanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Ładowanie...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Wsuwanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Oczyszczanie...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); From 0f0b1aff551ff8cdf52ea9f3169a5a71b84c21af Mon Sep 17 00:00:00 2001 From: android444 Date: Thu, 16 Apr 2020 10:41:27 +0200 Subject: [PATCH 0170/1454] Update GLCD Silvergate display timing (#17518) --- Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h index c6e0b9944b..6297b2f7a9 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h @@ -46,11 +46,11 @@ #define CPU_ST7920_DELAY_1 DELAY_NS(0) #define CPU_ST7920_DELAY_2 DELAY_NS(0) #define CPU_ST7920_DELAY_3 DELAY_NS(50) -#elif MB(3DRAG, K8200, K8400, SILVER_GATE) +#elif MB(3DRAG, K8200, K8400) #define CPU_ST7920_DELAY_1 DELAY_NS(0) #define CPU_ST7920_DELAY_2 DELAY_NS(188) #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(MINIRAMBO, EINSY_RAMBO, EINSY_RETRO) +#elif MB(MINIRAMBO, EINSY_RAMBO, EINSY_RETRO, SILVER_GATE) #define CPU_ST7920_DELAY_1 DELAY_NS(0) #define CPU_ST7920_DELAY_2 DELAY_NS(250) #define CPU_ST7920_DELAY_3 DELAY_NS(0) From 7d0ea3e2c46698942c7262dfdd003128013f49a6 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Thu, 16 Apr 2020 01:43:32 -0700 Subject: [PATCH 0171/1454] Fix framework-arduinoststm32 minimum version (#17512) --- platformio.ini | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/platformio.ini b/platformio.ini index 63df14cf63..aab3198bfd 100644 --- a/platformio.ini +++ b/platformio.ini @@ -631,7 +631,7 @@ lib_ignore = Adafruit NeoPixel [env:STM32F401VE_STEVAL] platform = ststm32 board = STEVAL_STM32F401VE -platform_packages = framework-arduinoststm32@>=3.107,<4 +platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" @@ -649,7 +649,7 @@ src_filter = ${common.default_src_filter} + [env:FLYF407ZG] platform = ststm32 board = FLYF407ZG -platform_packages = framework-arduinoststm32@>=3.107,<4 +platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DSTM32F4 -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x8000 @@ -668,7 +668,7 @@ platform = ststm32 board = fysetc_s6 platform_packages = tool-stm32duino - framework-arduinoststm32@>=3.107,<4 + framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -std=gnu++14 -DVECT_TAB_OFFSET=0x10000 @@ -689,7 +689,7 @@ upload_protocol = serial [env:STM32F407VE_black] platform = ststm32 board = blackSTM32F407VET6 -platform_packages = framework-arduinoststm32@>=3.107,<4 +platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\" @@ -705,7 +705,7 @@ src_filter = ${common.default_src_filter} + [env:BIGTREE_SKR_PRO] platform = ststm32 board = BigTree_SKR_Pro -platform_packages = framework-arduinoststm32@>=3.107,<4 +platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 @@ -725,7 +725,7 @@ debug_init_break = [env:BIGTREE_GTR_V1_0] platform = ststm32@>=5.7.0 framework = arduino -platform_packages = framework-arduinoststm32@>=3.107,<4 +platform_packages = framework-arduinoststm32@>=3.10700,<4 board = BigTree_SKR_Pro extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common.build_flags} @@ -749,7 +749,7 @@ monitor_speed = 250000 [env:BIGTREE_BTT002] platform = ststm32@5.6.0 board = BigTree_Btt002 -platform_packages = framework-arduinoststm32@>=3.107,<4 +platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407VG\" -DTARGET_STM32F4 -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 From d194688020d37cb53676f77693eeb5d18f4d5b37 Mon Sep 17 00:00:00 2001 From: dandantsui <62964600+dandantsui@users.noreply.github.com> Date: Thu, 16 Apr 2020 01:53:58 -0700 Subject: [PATCH 0172/1454] Define EEPROM, SD type for MKS Robin nano (#17498) --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index ae9118e6d0..5a4ac26617 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -38,6 +38,12 @@ // #define DISABLE_DEBUG +// +// EEPROM +// +//#define FLASH_EEPROM_EMULATION +#define SDCARD_EEPROM_EMULATION + // // Limit Switches // @@ -106,6 +112,10 @@ // // SD Card // +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + #define SDIO_SUPPORT #define SD_DETECT_PIN PD12 From f5d809f3667846e962c86d1d4f4b8ac97e8a3e5f Mon Sep 17 00:00:00 2001 From: Bob Kuhn Date: Thu, 16 Apr 2020 03:55:33 -0500 Subject: [PATCH 0173/1454] SKR Pro 1.1 WiFi and LCD SD card support (#17531) --- Marlin/src/HAL/shared/esp_wifi.cpp | 35 +++++++++++++++++ Marlin/src/HAL/shared/esp_wifi.h | 24 ++++++++++++ Marlin/src/MarlinCore.cpp | 3 ++ Marlin/src/pins/pinsDebug_list.h | 6 +++ .../src/pins/stm32f4/pins_BLACK_STM32F407VE.h | 6 ++- .../src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 39 ++++++++++++++++--- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 6 ++- 7 files changed, 111 insertions(+), 8 deletions(-) create mode 100644 Marlin/src/HAL/shared/esp_wifi.cpp create mode 100644 Marlin/src/HAL/shared/esp_wifi.h diff --git a/Marlin/src/HAL/shared/esp_wifi.cpp b/Marlin/src/HAL/shared/esp_wifi.cpp new file mode 100644 index 0000000000..ab073d6f08 --- /dev/null +++ b/Marlin/src/HAL/shared/esp_wifi.cpp @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" +#include "Delay.h" + +void esp_wifi_init(void) { + #if PIN_EXISTS(ESP_WIFI_MODULE_RESET) + OUT_WRITE(ESP_WIFI_MODULE_RESET_PIN, LOW); + delay(1); + OUT_WRITE(ESP_WIFI_MODULE_RESET_PIN, HIGH); + #endif + #if PIN_EXISTS(ESP_WIFI_MODULE_ENABLE) + OUT_WRITE(ESP_WIFI_MODULE_ENABLE_PIN, HIGH); + #endif +} diff --git a/Marlin/src/HAL/shared/esp_wifi.h b/Marlin/src/HAL/shared/esp_wifi.h new file mode 100644 index 0000000000..e8aa50446b --- /dev/null +++ b/Marlin/src/HAL/shared/esp_wifi.h @@ -0,0 +1,24 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +void esp_wifi_init(); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index e4fbf31a27..759d3b2132 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -44,6 +44,7 @@ #include "feature/closedloop.h" #include "HAL/shared/Delay.h" +#include "HAL/shared/esp_wifi.h" #include "module/stepper/indirection.h" @@ -962,6 +963,8 @@ void setup() { BOARD_INIT(); #endif + SETUP_RUN(esp_wifi_init()); + // Check startup - does nothing if bootloader sets MCUSR to 0 byte mcu = HAL_get_reset_source(); if (mcu & 1) SERIAL_ECHOLNPGM(STR_POWERUP); diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 28478973fb..bb7ececa92 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -1409,3 +1409,9 @@ #if PIN_EXISTS(CLOSED_LOOP_MOVE_COMPLETE) REPORT_NAME_DIGITAL(__LINE__, CLOSED_LOOP_MOVE_COMPLETE_PIN) #endif +#if PIN_EXISTS(ESP_WIFI_MODULE_RESET) + REPORT_NAME_DIGITAL(__LINE__, ESP_WIFI_MODULE_RESET_PIN) +#endif +#if PIN_EXISTS(ESP_WIFI_MODULE_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, ESP_WIFI_MODULE_ENABLE_PIN) +#endif diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index f9b548420d..1a6bd80ae6 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -142,7 +142,11 @@ #define SDIO_CK_PIN PC12 #define SDIO_CMD_PIN PD2 -#if !defined(SDCARD_CONNECTION) || SD_CONNECTION_IS(ONBOARD) +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 77acbc5b48..84b9796774 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -31,7 +31,7 @@ // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation // // Servos @@ -215,7 +215,11 @@ #define HEATER_BED_PIN PD12 // Hotbed #define FAN_PIN PC8 // Fan0 #define FAN1_PIN PE5 // Fan1 -#define FAN2_PIN PE6 // Fan2 +#define FAN2_PIN PE6 + +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PC9 +#endif // // Misc. Functions @@ -227,16 +231,14 @@ // // Onboard SD card -// NOT compatible with LCD +// Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // -#if SDCARD_CONNECTION == ONBOARD && !HAS_SPI_LCD +#if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI // Use soft SPI for onboard SD #define SDSS PA4 #define SCK_PIN PA5 #define MISO_PIN PA6 #define MOSI_PIN PB5 -#else - #define SDSS PB12 #endif /** @@ -256,6 +258,9 @@ #if HAS_SPI_LCD #define BEEPER_PIN PG4 #define BTN_ENC PA8 + #if SD_CONNECTION_IS(LCD) + #define SDSS PB12 // Uses default hardware SPI for LCD's SD + #endif #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS PG6 @@ -272,6 +277,10 @@ #undef ST7920_DELAY_2 #undef ST7920_DELAY_3 + #elif ENABLED(MKS_MINI_12864) + #define DOGLCD_A0 PG6 + #define DOGLCD_CS PG3 + #else #define LCD_PINS_RS PD10 @@ -321,3 +330,21 @@ #endif #endif // HAS_SPI_LCD + +// +// WIFI +// + +/** + * _____ + * TX | 1 2 | GND Enable PG1 // Must be high for module to run + * Enable | 3 4 | GPIO2 Reset PG0 // Leave as unused (OK to leave floating) + * Reset | 5 6 | GPIO0 GPIO2 PF15 // Leave as unused (best to leave floating) + * 3.3V| 7 8 | RX GPIO0 PF14 // Leave as unused (best to leave floating) + *  ̄ ̄ + * W1 + */ +#define ESP_WIFI_MODULE_COM 6 // must also set SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE //115200 // use BAUDRATE ? would guarantee same baud rate as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_RESET_PIN -1 +#define ESP_WIFI_MODULE_ENABLE_PIN PG1 diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index ffae5cc0ef..3681fde8d1 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -164,7 +164,11 @@ #define SDIO_CK_PIN PC12 #define SDIO_CMD_PIN PD2 -#if !defined(SDCARD_CONNECTION) || SD_CONNECTION_IS(ONBOARD) +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #ifndef SDIO_SUPPORT From aca2e149abc500a86fba0fd3166ea6a5215550e0 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Thu, 16 Apr 2020 10:58:29 +0200 Subject: [PATCH 0174/1454] Silence E3 DIP build warning (#17492) --- buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py b/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py index af4c66cd21..ecdd57f594 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py @@ -1,6 +1,10 @@ import os Import("env") +for define in env['CPPDEFINES']: + if define[0] == "VECT_TAB_ADDR": + env['CPPDEFINES'].remove(define) + # Relocate firmware from 0x08000000 to 0x08007000 env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08007000")) From 78a50795584948a3a17c044dda944072d0586ea9 Mon Sep 17 00:00:00 2001 From: "Zs.Antal" <45710979+AntoszHUN@users.noreply.github.com> Date: Thu, 16 Apr 2020 11:11:42 +0200 Subject: [PATCH 0175/1454] Add Hungarian language (#17491) Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 6 +- Marlin/Configuration_adv.h | 1 + Marlin/src/core/language.h | 1 + Marlin/src/lcd/dogm/fontdata/langdata_hu.h | 15 + Marlin/src/lcd/language/language_hu.h | 615 +++++++++++++++++++++ buildroot/share/fonts/genallfont.sh | 2 +- buildroot/share/tests/mega2560-tests | 4 +- 7 files changed, 638 insertions(+), 6 deletions(-) create mode 100644 Marlin/src/lcd/dogm/fontdata/langdata_hu.h create mode 100644 Marlin/src/lcd/language/language_hu.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index a4a91078ef..1e07ac49dc 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1611,10 +1611,10 @@ * * Select the language to display on the LCD. These languages are available: * - * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, it, jp_kana, - * ko_KR, nl, pl, pt, pt_br, ru, sk, tr, uk, vi, zh_CN, zh_TW, test + * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it, + * jp_kana, ko_KR, nl, pl, pt, pt_br, ru, sk, tr, uk, vi, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 91646d8854..dd9a8db6d6 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1413,6 +1413,7 @@ //#define LCD_LANGUAGE_3 de //#define LCD_LANGUAGE_4 es //#define LCD_LANGUAGE_5 it + //#define LCD_LANGUAGE_6 hu // Use a numeric passcode for "Screen lock" keypad. // (recommended for smaller displays) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index f4205d3f64..e662fffd37 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -57,6 +57,7 @@ // fr French // gl Galician // hr Croatian +// hu Hungarian // it Italian // jp_kana Japanese // ko_KR Korean (South Korea) diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h new file mode 100644 index 0000000000..29060b252a --- /dev/null +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h @@ -0,0 +1,15 @@ +/** + * Generated automatically by buildroot/share/fonts/uxggenpages.sh + * Contents will be REPLACED by future processing! + * Use genallfont.sh to generate font data for updated languages. + */ +#include + +const u8g_fntpgm_uint8_t fontpage_2_241_241[31] U8G_FONT_SECTION("fontpage_2_241_241") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x08,0x00,0x00, + 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x48,0x90,0x00,0x88,0x88,0x88,0x88,0x70}; + +#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } +static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { + FONTDATA_ITEM(2, 241, 241, fontpage_2_241_241), // 'ű' -- 'ű' +}; diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h new file mode 100644 index 0000000000..f282704abd --- /dev/null +++ b/Marlin/src/lcd/language/language_hu.h @@ -0,0 +1,615 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Hungarian + * + * LCD Menu Messages + * See also http://marlinfw.org/docs/development/lcd_language.html + * + */ + +namespace Language_hu { + using namespace Language_en; // Inherit undefined strings from English + + constexpr uint8_t CHARSIZE = 2; + PROGMEM Language_Str LANGUAGE = _UxGT("Magyar") + + PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Kész."); + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); + PROGMEM Language_Str MSG_YES = _UxGT("IGEN"); + PROGMEM Language_Str MSG_NO = _UxGT("NEM"); + PROGMEM Language_Str MSG_BACK = _UxGT("Vissza"); + PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Megszakítás..."); + PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tároló Behelyezve"); + PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tároló Eltávolítva"); + PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Tároló Leválasztva"); + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); + PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); + PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); + PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter + PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. Végállás"); + PROGMEM Language_Str MSG_MAIN = _UxGT(""); + PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("További Beállítások"); + PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguráció"); + PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autoinditás"); + PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motorok kikapcsolása"); + PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Hiba Menü"); + PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Haladás sáv teszt"); + PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("XYZ Auto kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X Kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y Kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z Kezdöpont"); + PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Igazítás"); + PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ Kezdöpont"); + PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kattints a kezdéshez."); + PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Következö Pont"); + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Szintezés Kész!"); + PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Szint Csökkentés"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); + PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preheat ") PREHEAT_1_LABEL; + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preheat ") PREHEAT_1_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Fej"); + PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Fej ~"); + PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Mind"); + PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Ágy"); + PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Beáll"); + PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Preheat ") PREHEAT_2_LABEL; + PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Preheat ") PREHEAT_2_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Fej"); + PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Fej ~"); + PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Mind"); + PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Ágy"); + PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Beáll"); + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Egyedi Elömelegítés"); + PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Visszahütés"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lézer Vezérlés"); + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Lézer Ki"); + PROGMEM Language_Str MSG_LASER_ON = _UxGT("Lézer Be"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lézer Teljesítmény"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Orsó Vezérlés"); + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Orsó Ki"); + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Orsó Be"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Orsó Teljesítmény"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Orsó Hátra"); + PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Bekapcsolás"); + PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Kikapcsolás"); + PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudál"); + PROGMEM Language_Str MSG_RETRACT = _UxGT("Visszahúz"); + PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Tengelyek Mozgatása"); + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ágy Szintezés"); + PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ágy szintezése"); + PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Sarok szint"); + PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Következö sarok"); + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Háló Szerkesztö"); + PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Háló Szerkesztése"); + PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Háló Szerk. Állj"); + PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Próbapont"); + PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); + PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); + PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Érték"); + PROGMEM Language_Str MSG_USER_MENU = _UxGT("Egyéni Parancs"); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probe Teszt"); + PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Pont"); + PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Eltérés"); + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX Mód"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Eszköz Eltolás"); + PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkolás"); + PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikálás"); + PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Tükrözött másolás"); + PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Teljes felügyelet"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. fúvóka X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. fúvóka Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. fúvóka Z"); + PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Szintezz! G29"); + PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Eszköz"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Egységes Ágy Szint"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Döntési Pont"); + PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Kézi Háló Építés"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Tégy alátétet és mérj"); + PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mérés"); + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Üres ágyat mérj"); + PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Továbblépés"); + PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL Aktivál"); + PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL Deaktivál"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ágy Höfok"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Ágy Höfok"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fúvóka Höfok"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Fúvóka Höfok"); + PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Háló Szerkesztés"); + PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni Háló Szerkesztés"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított Háló"); + PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Háló Kész"); + PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Egyéni Háló Építés"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Háló Építés"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M1 = _UxGT("Háló Építés (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M2 = _UxGT("Háló Építés (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Hideg Háló Építés"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("AHáló Magasság Állítása"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Összmagasság"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Háló Elfogadás"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("Háló Elfogadás (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("Háló Elfogadás (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valódi Háló Elfogadása"); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Ágy Fűtés"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Fúvóka Fűtés"); + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Kézi alapozás..."); + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Fix hosszúságú alap"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Alapozás Kész"); + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Törölve"); + PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Kilépö G26"); + PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Ágy Háló Folyt."); + PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Háló Szintezés"); + PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Pontos Szintezés"); + PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rács Szintezés"); + PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Háló Szint"); + PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Oldal pontok"); + PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Térkép Típus"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Háló Térkép Kimenet"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host Kimenet"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV Kimenet"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Nyomtató Backup Ki"); + PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("UBL Infó Kimenet"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Kitöltési Költség"); + PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Kézi Kitöltés"); + PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Okos Kitöltés"); + PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Háló Kitöltés"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Minden Érvénytelen"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Közelebbi Érvénytelen"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Mindet Finomhangolja"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Közelebbi Finomhangolása"); + PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Háló Tárolás"); + PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memória Foglalat"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ágy háló Betöltés"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Ágy háló Mentés"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Háló %i Betöltve"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Háló %i Mentve"); + PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nincs tároló"); + PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Hiba: UBL Mentés"); + PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Hiba: UBL Visszaáll"); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Eltolás: "); + PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Eltolás Leállítva"); + PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Lépésröl Lépésre UBL"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Hideg Háló Készítés"); + PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligens Kitöltés"); + PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Háló Érvényesítés"); + PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Minden Finomítása"); + PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Háló Érvényesítés"); + PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Minden Finomítása"); + PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Ágy Háló Mentése"); + + PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Vezérlés"); + PROGMEM Language_Str MSG_LEDS = _UxGT("Világítás"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított Fény"); + PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Piros"); + PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Narancs"); + PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Sárga"); + PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Zöld"); + PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Kék"); + PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigó"); + PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); + PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Fehér"); + PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni Fény"); + PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros Intenzitás"); + PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld Intenzitás"); + PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Kék Intenzitás"); + PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Fehér Intenzitás"); + PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Fényerö"); + + PROGMEM Language_Str MSG_MOVING = _UxGT("Mozgás..."); + PROGMEM Language_Str MSG_FREE_XY = _UxGT("XY Szabad"); + PROGMEM Language_Str MSG_MOVE_X = _UxGT("X Mozgás"); + PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Y Mozgás"); + PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Z Mozgás"); + PROGMEM Language_Str MSG_MOVE_E = _UxGT("Adagoló"); + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Adagoló *"); + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("A fúvóka túl hideg"); + PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mozgás %smm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); + PROGMEM Language_Str MSG_SPEED = _UxGT("Sebesség"); + PROGMEM Language_Str MSG_BED_Z = _UxGT("Z ágy"); + PROGMEM Language_Str MSG_NOZZLE = _UxGT("Fúvóka"); + PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Fúvóka ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Fej Parkolva"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Fej Készenlétbe"); + PROGMEM Language_Str MSG_BED = _UxGT("Ágy"); + PROGMEM Language_Str MSG_CHAMBER = _UxGT("Burkolat"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Hütés sebesség"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Tárolt Hütés ="); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra hütés sebesség"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra hütés sebesség ="); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Hűtésvezérlés"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Alapjárat"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Automatikus Mód"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív Sebesség"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Készenlét"); + PROGMEM Language_Str MSG_FLOW = _UxGT("Folyás"); + PROGMEM Language_Str MSG_FLOW_N = _UxGT("Folyás ~"); + PROGMEM Language_Str MSG_CONTROL = _UxGT("Konfiguráció"); + PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tény"); + PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Automata Höfok"); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("Be"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Ki"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Hangolás"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Hangolás *"); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); + PROGMEM Language_Str MSG_SELECT = _UxGT("Kiválaszt"); + PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); + PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); + PROGMEM Language_Str MSG_JERK = _UxGT("Rántás"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Rántás"); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont Eltérés"); + PROGMEM Language_Str MSG_VELOCITY = _UxGT("Sebesség"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Sebesség ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max Sebesség ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max Sebesség ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Sebesség ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max Sebesség *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Min Sebesség"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Utazó.Seb."); + PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Gyorsulás"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Gyorsulás ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Gyorsulás ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Gyorsulás ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Gyorsulás ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Gyorsulás *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Szál visszahúzás"); + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Utazás"); + PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("lépés/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("lépés/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("lépés/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E lépés/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*lépés/mm"); + PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Höfok"); + PROGMEM Language_Str MSG_MOTION = _UxGT("Mozgatások"); + PROGMEM Language_Str MSG_FILAMENT = _UxGT("Nyomtatószál"); + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E mm³-ben"); + PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Szál. Átm."); + PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Szál. Átm. *"); + PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Kiadás mm"); + PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Betöltés mm"); + PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Haladó K"); + PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Haladó K *"); + PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontraszt"); + PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Tárolás EEPROM"); + PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Betöltés EEPROM"); + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Alapértelmezett"); + PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM Inicializálás"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: EEPROM Index"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: EEPROM Verzió"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Beállítások Mentve"); + PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Tároló Frissítés"); + PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Nyomtató Újraindítása"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Frissítés"); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Infó Képernyö"); + PROGMEM Language_Str MSG_PREPARE = _UxGT("Vezérlés"); + PROGMEM Language_Str MSG_TUNE = _UxGT("Hangolás"); + PROGMEM Language_Str MSG_START_PRINT = _UxGT("Nyomtatás Indítása"); + PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Tovább"); + PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Kezdet"); + PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Állj"); + PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Nyomtatás"); + PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Újraindítás"); + PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Mégse"); + PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Kész"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Vissza"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Folytatás"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Szüneteltetve..."); + PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Nyomtatás Szünetelés"); + PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Nyomtatás folytatása"); + PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Nyomtatás leállítása"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Objektum Nyomtatása"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objektum Törlése"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objektum Törlése ="); + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Kiesés Helyreáll."); + PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Nyomtatás Tárolóról"); + PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Nincs Tároló"); + PROGMEM Language_Str MSG_DWELL = _UxGT("Alvás..."); + PROGMEM Language_Str MSG_USERWAIT = _UxGT("Katt a folytatáshoz..."); + PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Nyomtatás szünetelve"); + PROGMEM Language_Str MSG_PRINTING = _UxGT("Nyomtatás..."); + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Nyomtatás leállítva"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Nyomtatás Kész"); + PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Nincs mozgás."); + PROGMEM Language_Str MSG_KILLED = _UxGT("HALOTT! "); + PROGMEM Language_Str MSG_STOPPED = _UxGT("MEGÁLLT! "); + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Visszahúzás mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Visszahúzás Cs. mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Viszahúzás"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Ugrás mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Visszah.helyre mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Csere.Visszah.helyre mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("UnRet V"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoVisszah."); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás Távolság"); + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási Távolság"); + PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Szerszámcsere"); + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Emelés"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Fösebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Visszah. Sebesség"); + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Szál csere"); + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Szál csere *"); + PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Szál betöltés"); + PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Szál betöltés *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Szál eltávolítás"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Szál eltávolítás *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Mindet Eltávolít"); + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Tároló"); + PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Tároló csere"); + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Tároló Kiadása"); + PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z szonda tálcán kivül"); + PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Ferdeség Faktor"); + PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Cmd: Önteszt"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Cmd: Visszaállítás"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Cmd: Elhelyez"); + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Cmd: Telepít"); + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Cmd: SW-Mód"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Cmd: 5V-Mód"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Cmd: OD-Mód"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Cmd: Módok"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V Mód"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD Mód"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Jelentés"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("VESZÉLY: A rossz beállítások kárt okozhatnak! Biztos továbblép?"); + PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Kezd TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Teszt"); + PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Mentés"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI Használ"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Probe Használ"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Probe Elhelyezés"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Elsö %s%s%s Kell"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Szonda Eltolások"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Szonda X Eltolás"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Szonda Y Eltolás"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Szonda Z Eltolás"); + PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); + PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); + PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); + PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); + PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Ágy fütés hiba!"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Kamra fütés hiba!"); + PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Hiba: SZÜKSÉGTELEN HÖFOK"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FÜTÉS KIMARADÁS"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ÁGY FÜTÉS KIMARADÁS"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMRA FÜTÉS KIMARADÁS"); + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hiba: MAX Höfok"); + PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hiba: MIN Höfok"); + PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Hiba: MAX ÁGY HÖFOK"); + PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Hiba: MIN ÁGY HÖFOK"); + PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Hiba: MAX KAMRA HÖFOK"); + PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Hiba: MIN KAMRA HÖFOK"); + PROGMEM Language_Str MSG_ERR_Z_HOMING = _UxGT("XY Kezdöpont"); + PROGMEM Language_Str MSG_HALTED = _UxGT("A NYOMTATÓ LEFAGYOTT"); + PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Indítsd újra!"); + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // Csak egy karakter + PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("ó"); // Csak egy karakter + PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("p"); // Csak egy karakter + PROGMEM Language_Str MSG_HEATING = _UxGT("Fütés..."); + PROGMEM Language_Str MSG_COOLING = _UxGT("Hütés..."); + PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Ágy fütés..."); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Ágy hütés..."); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Kamra fütés..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Kamra hütés..."); + PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibráció"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("X Kalibrálás"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Y Kalibrálás"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Z Kalibrálás"); + PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ Kalibrálás"); + PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta Beállítások"); + PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibráció"); + PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Magasság Kalib."); + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z Szonda Eltolás"); + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag Rúd"); + PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Magasság"); + PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Sugár"); + PROGMEM Language_Str MSG_INFO_MENU = _UxGT("A Nyomtatóról"); + PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Nyomtató Infó"); + PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Pontos Szintezés"); + PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris Szintezés"); + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris Szintezés"); + PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes Ágy Szintezés"); + PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló Szintezés"); + PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Nyomtató Statisztika"); + PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap Infó"); + PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); + PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruderek"); + PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Átviteli sebesség"); + PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Futáselemzés: KI"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Futáselemzés: BE"); + + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Munkalámpa"); + PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Fényerösség"); + PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); + + #if LCD_WIDTH >= 20 + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás Számláló"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Összes nyomtatási idö"); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb munkaidö"); + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Összes anyag"); + #else + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatások"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Összes"); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb"); + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Kiadott"); + #endif + + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Höfok"); + PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Höfok"); + PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); + PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Meghajtási Erö"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Meghajtó %"); + PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); + PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Írása"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("NYOMTATÓSZÁL CSERE"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("NYOMTATÁS SZÜNETEL"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("SZÁL BETÖLTÉS"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("SZÁL ELTÁVOLÍTÁS"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FOLYTATÁSI OPCIÓ:"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Tisztítsd meg"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Folytatás"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Fúvóka: "); + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Túlfutás Szenzor"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás Táv. mm"); + PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Tájolási hiba"); + PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Szondázás hiba"); + PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Túl hideg"); + + PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SZÁLVÁLASZTÁS"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("MMU Szoftver Feltöltése!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Figyelmeztetés."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Nyomtatás Folytatása"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Folytatás..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál Betöltése"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Összes Betöltése"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fúvóka Betöltése"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál Kiadása"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál Kiadása ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Kiadja a szálat"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Szál betölt. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kiadás...."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Szál kiadása...."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Mind"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Nyomtatószál ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU Újraindítás"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Újraindul..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Eltávolít, kattint"); + + PROGMEM Language_Str MSG_MIX = _UxGT("Kever"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); + PROGMEM Language_Str MSG_MIXER = _UxGT("Keverö"); + PROGMEM Language_Str MSG_GRADIENT = _UxGT("Színátm."); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Teljes Színátm."); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Váltás Keverésre"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Ciklikus Keverés"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Színátm. Keverés"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Fordított Színátm."); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktív V-szerszám"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Kezdés V-szerszám"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Vége V-szerszám"); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Ál V-szerszám"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Újra V-szerszám"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Gyors V-szerszám Kev."); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-szersz. visszaáll."); + PROGMEM Language_Str MSG_START_Z = _UxGT("Kezdés Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" Vége Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Játékok"); + PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + + // + // Filamentváltó képernyők legfeljebb 3 sort jeleníthetnek meg egy 4 soros kijelzőn + // ...vagy legfeljebb 2 sor egy 3 soros kijelzőn + // + #if LCD_HEIGHT >= 4 + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nyomj gombot", "nyomtatás folytatáshoz")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkolás...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Várj míg", "szál csere", "indítás")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Szál behelyezés", "majd nyomj gombot", "a folytatáshoz")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nyomj gombot", "a fúvóka fűtéséhez")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Fúvóka fűtése", "Kérlek várj...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Várj a", "szál kiadására")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Várj a", "szál betöltésére")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Várj a", "szál tisztításra")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kattints a készre", "szál tiszta")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd foltyat...")); + #else + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkolás...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Kérlek Várj...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Behelyez majd katt")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Katt a fűtéshez")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Fűtés...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Kiadás...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Betöltés...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Tisztítás...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Katt ha kész")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Folytatás...")); + #endif + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Meghajtók"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Meghajtó áram"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrid Küszöbérték"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Motoros Kezdöpont"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Léptetö Mód"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Aktív"); + PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Újraindítás"); + PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" be:"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Holtjáték"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrekció"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Simítás"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X Tengely Szint"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Önkalibrálás"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Fűtéskimaradás"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Újrafűt"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Újrafűtés..."); +} + +#if FAN_COUNT == 1 + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED + #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED +#else + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N + #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED_N +#endif diff --git a/buildroot/share/fonts/genallfont.sh b/buildroot/share/fonts/genallfont.sh index 7d4b551776..e41baac263 100755 --- a/buildroot/share/fonts/genallfont.sh +++ b/buildroot/share/fonts/genallfont.sh @@ -62,7 +62,7 @@ OLDWD=`pwd` # # By default loop through all languages # -LANGS_DEFAULT="an bg ca cz da de el el_gr en es eu fi fr gl hr it jp_kana ko_KR nl pl pt pt_br ru sk tr uk vi zh_CN zh_TW test" +LANGS_DEFAULT="an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana ko_KR nl pl pt pt_br ru sk tr uk vi zh_CN zh_TW test" # # Generate data for language list MARLIN_LANGS or all if not provided diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index 884ea8be4a..8c6c025aee 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -231,11 +231,11 @@ exec_test $1 $2 "Megatronics 3.2 | Gradient Mix | Endstop Int. | Home Y > X | FW # #restore_configs #opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT -#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr it jp_kana nl pl pt pt_br ru sk tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff"; done +#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ru sk tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff"; done # #restore_configs #opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT -#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr it jp_kana nl pl pt pt_br ru sk tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff"; done +#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ru sk tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff"; done ######## Example Configurations ############## # From c16818b26133976ec9cf90c909627d34d6e24f37 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Thu, 16 Apr 2020 11:38:17 +0200 Subject: [PATCH 0176/1454] Fix SAMD51 timer usage (#17471) --- Marlin/src/HAL/SAMD51/Servo.cpp | 8 ++++---- Marlin/src/HAL/SAMD51/inc/SanityCheck.h | 4 ++++ 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index b39869ef32..c7cff45434 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -55,7 +55,7 @@ static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval) FORCE_INLINE static uint16_t getTimerCount() { - Tc * const tc = TimerConfig[SERVO_TC].pTimer; + Tc * const tc = TimerConfig[SERVO_TC].pTc; tc->COUNT16.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC; SYNC(tc->COUNT16.SYNCBUSY.bit.CTRLB || tc->COUNT16.SYNCBUSY.bit.COUNT); @@ -67,7 +67,7 @@ FORCE_INLINE static uint16_t getTimerCount() { // Interrupt handler for the TC // ---------------------------- HAL_SERVO_TIMER_ISR() { - Tc * const tc = TimerConfig[SERVO_TC].pTimer; + Tc * const tc = TimerConfig[SERVO_TC].pTc; const timer16_Sequence_t timer = #ifndef _useTimer1 _timer2 @@ -127,7 +127,7 @@ HAL_SERVO_TIMER_ISR() { } void initISR(timer16_Sequence_t timer) { - Tc * const tc = TimerConfig[SERVO_TC].pTimer; + Tc * const tc = TimerConfig[SERVO_TC].pTc; const uint8_t tcChannel = TIMER_TCCHANNEL(timer); static bool initialized = false; // Servo TC has been initialized @@ -204,7 +204,7 @@ void initISR(timer16_Sequence_t timer) { } void finISR(timer16_Sequence_t timer) { - Tc * const tc = TimerConfig[SERVO_TC].pTimer; + Tc * const tc = TimerConfig[SERVO_TC].pTc; const uint8_t tcChannel = TIMER_TCCHANNEL(timer); // Disable the match channel interrupt request diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h index cc7a10e7a6..d695db6e17 100644 --- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -35,6 +35,10 @@ #error "OnBoard SPI BUS can't be shared with other devices." #endif +#if SERVO_TC == RTC_TIMER_NUM + #error "Servos can't use RTC timer" +#endif + #if ENABLED(EMERGENCY_PARSER) #error "EMERGENCY_PARSER is not yet implemented for SAMD51. Disable EMERGENCY_PARSER to continue." #endif From f5577b320b98bf515d7c7fe69e6306c9e21547ac Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Thu, 16 Apr 2020 11:39:01 +0200 Subject: [PATCH 0177/1454] Update Italian language (#17467) --- Marlin/src/lcd/language/language_it.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 1870957401..0aed8a6cfa 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -50,6 +50,7 @@ namespace Language_it { PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo media"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Overflow subchiamate"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Finecor."); // Max 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principale"); @@ -321,6 +322,7 @@ namespace Language_it { PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: CRC EEPROM"); PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: Indice EEPROM"); PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versione EEPROM"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Impostazioni mem."); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aggiorna media"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetta stampante"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna"); @@ -337,6 +339,7 @@ namespace Language_it { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fatto"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Indietro"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Procedi"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Messa in pausa..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausa stampa"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Riprendi stampa"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Arresta stampa"); From d353d67a34637c8ad2039444b79748b6f913767c Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Thu, 16 Apr 2020 05:41:05 -0400 Subject: [PATCH 0178/1454] SD detect override for older Creality3D RAMPS (#17469) --- Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index f6847feb4b..5134812c1b 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -39,7 +39,9 @@ #define FIL_RUNOUT2_PIN 15 // Creality CR-X can use dual runout sensors #endif -#define SD_DETECT_PIN 49 // Always define onboard SD detect +#ifndef SD_DETECT_PIN + #define SD_DETECT_PIN 49 // Always define onboard SD detect +#endif #define PS_ON_PIN 40 // Used by CR2020 Industrial series From 847ea583f624328f9fcc97d1354f5c2bcb991960 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Apr 2020 15:34:44 -0500 Subject: [PATCH 0179/1454] STM32F103VE has 512K Flash EEPROM (#17565) --- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 4 ++-- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 4 ++-- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 4 ++-- Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h | 5 +++-- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 4 ++-- Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 6 +++--- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 6 +++--- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 4 ++-- platformio.ini | 13 ++++++------- 10 files changed, 26 insertions(+), 26 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index ff42beb92a..629e455871 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -52,7 +52,7 @@ // ------------------------ #ifndef STM32_FLASH_SIZE - #ifdef MCU_STM32F103RE + #if defined(MCU_STM32F103RE) || defined(MCU_STM32F103VE) #define STM32_FLASH_SIZE 512 #else #define STM32_FLASH_SIZE 256 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 89e184524c..569e29a96a 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -34,8 +34,8 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 #define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE uint16(0x800) // 2KB -#define EEPROM_START_ADDRESS uint32(0x8000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) +#define EEPROM_PAGE_SIZE (0x800U) // 2KB +#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #undef E2END #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index d7a72592ef..5896f38f3d 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -32,8 +32,8 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 #define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE uint16(0x800) // 2KB -#define EEPROM_START_ADDRESS uint32(0x8000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) +#define EEPROM_PAGE_SIZE (0x800U) // 2KB +#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #undef E2END #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 8d2d18566d..39c70f0417 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -34,8 +34,8 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 #define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE (0x800) // 2KB -#define EEPROM_START_ADDRESS uint32(0x8000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) +#define EEPROM_PAGE_SIZE (0x800U) // 2KB +#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define E2END (EEPROM_PAGE_SIZE - 1) // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index dcd1119c86..ab6757d682 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -39,10 +39,11 @@ // Flash EEPROM Emulation // #define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE uint16(0x800) // 2KB -#define EEPROM_START_ADDRESS uint32(0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) +#define EEPROM_PAGE_SIZE (0x800U) // 2KB +#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #undef E2END #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB + // // Limit Switches // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index e726ca1831..b2cdd1c5db 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -36,8 +36,8 @@ #define DISABLE_JTAG #define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE uint16(0x800) // 2KB -#define EEPROM_START_ADDRESS uint32(0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) +#define EEPROM_PAGE_SIZE (0x800U) // 2KB +#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #undef E2END #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 6395f6efc9..0a4382894f 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -43,10 +43,10 @@ // Enable EEPROM Emulation for this board, so that we don't overwrite factory data //#define I2C_EEPROM // AT24C64 -//#define E2END 0x7FFF // 64KB +//#define E2END 0x7FFFUL // 64KB //#define FLASH_EEPROM_EMULATION -//#define E2END 0xFFF // 4KB -//#define E2END uint32(EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE * 2) - 1) +//#define E2END 0xFFFUL // 4KB +//#define E2END (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL - 1UL) //#define EEPROM_CHITCHAT //#define DEBUG_EEPROM_READWRITE diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 83881c128d..50ac8c94be 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -159,11 +159,11 @@ #define EEPROM_MISO BOARD_SPI1_MISO_PIN // PA6 pin 31 #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) - #define E2END ((16 * EEPROM_PAGE_SIZE)-1) // Limit to 64KB for now... + #define E2END (16UL * (EEPROM_PAGE_SIZE) - 1UL) // Limit to 64KB for now... #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) - #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define E2END (EEPROM_PAGE_SIZE - 1) #else #define E2END (0x7FFU) // On SD, Limit to 2KB, require this amount of RAM diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 50babad274..ff210c4cff 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -40,8 +40,8 @@ #define FLASH_EEPROM_EMULATION // 2K in a AT24C16N -#define EEPROM_PAGE_SIZE (uint16)0x800 // 2048 -#define EEPROM_START_ADDRESS ((uint32)(0x8000000 + 512 * 1024 - 2 * EEPROM_PAGE_SIZE)) +#define EEPROM_PAGE_SIZE (0x800U) // 2KB +#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define E2END (EEPROM_PAGE_SIZE - 1) // diff --git a/platformio.ini b/platformio.ini index aab3198bfd..0828170e44 100644 --- a/platformio.ini +++ b/platformio.ini @@ -463,9 +463,9 @@ src_filter = ${common.default_src_filter} + platform = ststm32 board = genericSTM32F103VE build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=DEBUG_NONE -std=gnu++14 -MMD -ffunction-sections -fdata-sections -nostdlib - -DBOARD_generic_stm32f103v -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 + ${common.build_flags} -std=gnu++14 -ffunction-sections -fdata-sections -nostdlib -MMD + -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v + -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, SPI @@ -478,8 +478,7 @@ upload_protocol = serial platform = ststm32 board = genericSTM32F103VE build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -USERIAL_USB - -DSTM32F1xx -DU20 -DTS_V12 + ${common.build_flags} -std=gnu++14 -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 build_unflags = -std=gnu++11 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py src_filter = ${common.default_src_filter} + @@ -492,7 +491,7 @@ lib_ignore = Adafruit NeoPixel, LiquidTWI2, SPI platform = ststm32 board = genericSTM32F103VE build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 + ${common.build_flags} -std=gnu++14 -DMCU_STM32F103VE build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_mini.py src_filter = ${common.default_src_filter} + @@ -506,7 +505,7 @@ platform = ststm32 board = genericSTM32F103VE platform_packages = tool-stm32duino build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 + ${common.build_flags} -std=gnu++14 -DMCU_STM32F103VE -DHAVE_SW_SERIAL -DSS_TIMER=4 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_nano.py src_filter = ${common.default_src_filter} + From 720795ac7d18522e5403412c310b5b63b02b1e98 Mon Sep 17 00:00:00 2001 From: Davide Toldo Date: Thu, 16 Apr 2020 23:22:37 +0200 Subject: [PATCH 0180/1454] More verbose probing error (#17482) --- Marlin/src/module/probe.cpp | 41 +++++++++++++++++++++---------------- 1 file changed, 23 insertions(+), 18 deletions(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index b4912d30c4..a96a9d5e9d 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -547,6 +547,25 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { if (DEBUGGING(LEVELING)) DEBUG_POS(">>> Probe::run_z_probe", current_position); + auto try_to_probe = [&](PGM_P const plbl, const float &z_probe_low_point, const feedRate_t fr_mm_s, const bool scheck, const float clearance) { + // Do a first probe at the fast speed + const bool probe_fail = probe_down_to_z(z_probe_low_point, fr_mm_s), // No probe trigger? + early_fail = (scheck && current_position.z > -offset.z + clearance); // Probe triggered too high? + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING) && (probe_fail || early_fail)) { + DEBUG_PRINT_P(plbl); + DEBUG_ECHOPGM(" Probe fail! -"); + if (probe_fail) DEBUG_ECHOPGM(" No trigger."); + if (early_fail) DEBUG_ECHOPGM(" Triggered early."); + DEBUG_EOL(); + DEBUG_POS("<<< run_z_probe", current_position); + } + #else + UNUSED(plbl); + #endif + return probe_fail || early_fail; + }; + // Stop the probe before it goes too low to prevent damage. // If Z isn't known then probe to -10mm. const float z_probe_low_point = TEST(axis_known_position, Z_AXIS) ? -offset.z + Z_PROBE_LOW_POINT : -10.0; @@ -555,15 +574,8 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #if TOTAL_PROBING == 2 // Do a first probe at the fast speed - if (probe_down_to_z(z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_FAST)) // No probe trigger? - || (sanity_check && current_position.z > -offset.z + _MAX(Z_CLEARANCE_BETWEEN_PROBES, 4) / 2) // Probe triggered too high? - ) { - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPGM("FAST Probe fail!"); - DEBUG_POS("<<< run_z_probe", current_position); - } - return NAN; - } + if (try_to_probe(PSTR("FAST"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_FAST), + sanity_check, _MAX(Z_CLEARANCE_BETWEEN_PROBES, 4) / 2) ) return NAN; const float first_probe_z = current_position.z; @@ -600,15 +612,8 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #endif { // Probe downward slowly to find the bed - if (probe_down_to_z(z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_SLOW)) // No probe trigger? - || (sanity_check && current_position.z > -offset.z + _MAX(Z_CLEARANCE_MULTI_PROBE, 4) / 2) // Probe triggered too high? - ) { - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPGM("SLOW Probe fail!"); - DEBUG_POS("<<< run_z_probe", current_position); - } - return NAN; - } + if (try_to_probe(PSTR("SLOW"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_SLOW), + sanity_check, _MAX(Z_CLEARANCE_MULTI_PROBE, 4) / 2) ) return NAN; #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) backlash.measure_with_probe(); From fd4c025e98783cbb55275cb5b58b6574a1311a32 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Fri, 17 Apr 2020 01:01:17 +0200 Subject: [PATCH 0181/1454] More features in SAMD51 test (#17572) --- .../share/tests/SAMD51_grandcentral_m4-tests | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/buildroot/share/tests/SAMD51_grandcentral_m4-tests b/buildroot/share/tests/SAMD51_grandcentral_m4-tests index f7157b1ed8..f93ef3343f 100644 --- a/buildroot/share/tests/SAMD51_grandcentral_m4-tests +++ b/buildroot/share/tests/SAMD51_grandcentral_m4-tests @@ -10,7 +10,31 @@ set -e # Build with the default configurations # restore_configs +opt_set SERIAL_PORT -1 opt_set MOTHERBOARD BOARD_AGCM4_RAMPS_144 +opt_set TEMP_SENSOR_0 11 +opt_set TEMP_SENSOR_BED 11 +opt_set X_DRIVER_TYPE TMC2209 +opt_set Y_DRIVER_TYPE TMC2209 +opt_set Z_DRIVER_TYPE TMC2209 +opt_set Z2_DRIVER_TYPE TMC2209 +opt_set E0_DRIVER_TYPE TMC2209 +opt_set RESTORE_LEVELING_AFTER_G28 false +opt_set LCD_LANGUAGE it +opt_set NUM_Z_STEPPER_DRIVERS 2 +opt_set X_HOME_BUMP_MM 0 +opt_set Y_HOME_BUMP_MM 0 +opt_set Z_HOME_BUMP_MM 0 +opt_set SDCARD_CONNECTION LCD +opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \ + FILAMENT_RUNOUT_SENSOR G26_MESH_VALIDATION MESH_EDIT_GFX_OVERLAY Z_SAFE_HOMING \ + EEPROM_SETTINGS NOZZLE_PARK_FEATURE SDSUPPORT SD_CHECK_AND_RETRY \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER Z_STEPPER_AUTO_ALIGN ADAPTIVE_STEP_SMOOTHING \ + STATUS_MESSAGE_SCROLLING LCD_SET_PROGRESS_MANUALLY SHOW_REMAINING_TIME USE_M73_REMAINING_TIME \ + LONG_FILENAME_HOST_SUPPORT SCROLL_LONG_FILENAMES BABYSTEPPING DOUBLECLICK_FOR_Z_BABYSTEPPING \ + MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ + LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ + SQUARE_WAVE_STEPPING TMC_DEBUG exec_test $1 $2 "Build Grand Central M4 Default Configuration" # clean up From 9110f756add41410a00559aafc603b89fd2d0af0 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Fri, 17 Apr 2020 02:03:53 +0200 Subject: [PATCH 0182/1454] AUTOTEMP default proportions (#17560) --- Marlin/Configuration_adv.h | 30 ++++++++++++++++++++---------- Marlin/src/module/planner.cpp | 15 ++++++++++++--- 2 files changed, 32 insertions(+), 13 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index dd9a8db6d6..af23f68a1a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -206,7 +206,7 @@ // A well-chosen Kc value should add just enough power to melt the increased material volume. //#define PID_EXTRUSION_SCALING #if ENABLED(PID_EXTRUSION_SCALING) - #define DEFAULT_Kc (100) //heating power=Kc*(e_speed) + #define DEFAULT_Kc (100) // heating power = Kc * e_speed #define LPQ_MAX_LEN 50 #endif @@ -262,18 +262,28 @@ #endif /** - * Automatic Temperature: - * The hotend target temperature is calculated by all the buffered lines of gcode. - * The maximum buffered steps/sec of the extruder motor is called "se". - * Start autotemp mode with M109 S B F - * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by - * mintemp and maxtemp. Turn this off by executing M109 without F* - * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp. - * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode + * Automatic Temperature Mode + * + * Dynamically adjust the hotend target temperature based on planned E moves. + * + * (Contrast with PID_EXTRUSION_SCALING, which tracks E movement and adjusts PID + * behavior using an additional kC value.) + * + * Autotemp is calculated by (mintemp + factor * mm_per_sec), capped to maxtemp. + * + * Enable Autotemp Mode with M104/M109 F S B. + * Disable by sending M104/M109 with no F parameter (or F0 with AUTOTEMP_PROPORTIONAL). */ #define AUTOTEMP #if ENABLED(AUTOTEMP) - #define AUTOTEMP_OLDWEIGHT 0.98 + #define AUTOTEMP_OLDWEIGHT 0.98 + // Turn on AUTOTEMP on M104/M109 by default using proportions set here + //#define AUTOTEMP_PROPORTIONAL + #if ENABLED(AUTOTEMP_PROPORTIONAL) + #define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature + #define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature + #define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F) + #endif #endif // Extra options for the M114 "Current Position" report diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index f6be8df9c9..c203306f65 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2973,9 +2973,18 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { #if ENABLED(AUTOTEMP) void Planner::autotemp_M104_M109() { - if ((autotemp_enabled = parser.seen('F'))) autotemp_factor = parser.value_float(); - if (parser.seen('S')) autotemp_min = parser.value_celsius(); - if (parser.seen('B')) autotemp_max = parser.value_celsius(); + + #if ENABLED(AUTOTEMP_PROPORTIONAL) + const int16_t target = thermalManager.degTargetHotend(active_extruder); + autotemp_min = target + AUTOTEMP_MIN_P; + autotemp_max = target + AUTOTEMP_MAX_P; + autotemp_factor = AUTOTEMP_FACTOR_P; + #endif + + if (parser.seenval('S')) autotemp_min = parser.value_celsius(); + if (parser.seenval('B')) autotemp_max = parser.value_celsius(); + if (parser.seenval('F')) autotemp_factor = parser.value_float(); + if (!autotemp_factor) autotemp_enabled = false; // F0 will disable autotemp } #endif From 3210155ab7735e97fd8b4a6568b3113b3a43f4eb Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 17 Apr 2020 02:04:43 +0200 Subject: [PATCH 0183/1454] Update French language (#17577) --- Marlin/src/lcd/language/language_fr.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index fa4c3c66ed..816113a208 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -284,6 +284,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Charger config."); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restaurer défauts"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initialiser EEPROM"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Config. enregistrée"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("MaJ Firmware SD"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("RaZ imprimante"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Actualiser"); @@ -300,6 +301,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Terminé"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Retour"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Procéder"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Mise en pause..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause impression"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Reprendre impr."); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Arrêter impr."); From 927e29b93ed433f1c55bb8afd9093054dd1bac80 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 17 Apr 2020 00:05:52 +0000 Subject: [PATCH 0184/1454] [cron] Bump distribution date (2020-04-17) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 83d5c7e73e..4b8fa39992 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-16" + #define STRING_DISTRIBUTION_DATE "2020-04-17" #endif /** From bbe2cb75adce137bfd11cd1283ca4e0f9c0ca647 Mon Sep 17 00:00:00 2001 From: XDA-Bam <1209896+XDA-Bam@users.noreply.github.com> Date: Fri, 17 Apr 2020 04:51:05 +0200 Subject: [PATCH 0185/1454] More accurate Junction Deviation fast-acos (#17575) --- Marlin/src/module/planner.cpp | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index c203306f65..e053676574 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2390,13 +2390,26 @@ bool Planner::_populate_block(block_t * const block, bool split_move, sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive. vmax_junction_sqr = (junction_acceleration * junction_deviation_mm * sin_theta_d2) / (1.0f - sin_theta_d2); - if (block->millimeters < 1) { - // Fast acos approximation, minus the error bar to be safe - const float junction_theta = (RADIANS(-40) * sq(junction_cos_theta) - RADIANS(50)) * junction_cos_theta + RADIANS(90) - 0.18f; + if (block->millimeters < 1) { + // Fast acos approximation (max. error +-0.033 rads) + // Based on MinMax polynomial published by W. Randolph Franklin, see + // https://wrf.ecse.rpi.edu/Research/Short_Notes/arcsin/onlyelem.html + // (acos(x) = pi / 2 - asin(x)) + + const float neg = junction_cos_theta < 0 ? -1 : 1, + t = neg * junction_cos_theta, + asinx = 0.032843707f + + t * (-1.451838349f + + t * ( 29.66153956f + + t * (-131.1123477f + + t * ( 262.8130562f + + t * (-242.7199627f + t * 84.31466202f) )))), + junction_theta = RADIANS(90) - neg * asinx; // If angle is greater than 135 degrees (octagon), find speed for approximate arc if (junction_theta > RADIANS(135)) { + // NOTE: MinMax acos approximation and thereby also junction_theta top out at pi-0.033, which avoids division by 0 const float limit_sqr = block->millimeters / (RADIANS(180) - junction_theta) * junction_acceleration; NOMORE(vmax_junction_sqr, limit_sqr); } From 3fcb36d8dc82a6c50e329d559184e108a2ae1da9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Apr 2020 03:43:48 -0500 Subject: [PATCH 0186/1454] M200/M300 LCD comment --- Marlin/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 1e07ac49dc..09942ace0e 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2069,7 +2069,7 @@ //#define DGUS_LCD_UI_HIPRECY // -// Touch-screen LCD for Malyan M200 printers +// Touch-screen LCD for Malyan M200/M300 printers // //#define MALYAN_LCD From 880f73d471d625f3e5eee7c4eb938bce7fca74cb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Apr 2020 04:35:00 -0500 Subject: [PATCH 0187/1454] Minor cleanup --- Marlin/Configuration_adv.h | 1 - Marlin/src/feature/leds/pca9533.h | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index af23f68a1a..1e29a355ff 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1423,7 +1423,6 @@ //#define LCD_LANGUAGE_3 de //#define LCD_LANGUAGE_4 es //#define LCD_LANGUAGE_5 it - //#define LCD_LANGUAGE_6 hu // Use a numeric passcode for "Screen lock" keypad. // (recommended for smaller displays) diff --git a/Marlin/src/feature/leds/pca9533.h b/Marlin/src/feature/leds/pca9533.h index a134ca15fd..fe299a754b 100644 --- a/Marlin/src/feature/leds/pca9533.h +++ b/Marlin/src/feature/leds/pca9533.h @@ -31,7 +31,7 @@ #define ENABLE_I2C_PULLUPS // Chip address (for Wire) -#define PCA9533_Addr 0xC4 +#define PCA9533_Addr 0xC4 // Control registers #define PCA9533_REG_READ 0x00 From e7f3b625b00957d587e9f2835b9a813ee72d6229 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Fri, 17 Apr 2020 14:19:47 +0200 Subject: [PATCH 0188/1454] Use 'melzi' envs for MELZI_CREALITY (#17578) --- Marlin/src/pins/pins.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 86cfd0b535..42b3c4e4e2 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -283,7 +283,7 @@ #elif MB(MELZI_MAKR3D) #include "sanguino/pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_CREALITY) - #include "sanguino/pins_MELZI_CREALITY.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p + #include "sanguino/pins_MELZI_CREALITY.h" // ATmega1284P env:melzi env:melzi_optiboot #elif MB(MELZI_MALYAN) #include "sanguino/pins_MELZI_MALYAN.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_TRONXY) From cbf349b5ebc21ba3784d5fe708614953fcd17d24 Mon Sep 17 00:00:00 2001 From: George Fu Date: Wed, 25 Mar 2020 16:10:58 +0800 Subject: [PATCH 0189/1454] Fix some DGUS bugs - No action on first click of the move button --- Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 7 +++++-- Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp | 2 +- Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp | 2 +- Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp | 2 +- 4 files changed, 8 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index bd73e811d1..a04d8a8807 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -443,6 +443,7 @@ void DGUSScreenVariableHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variab void DGUSScreenVariableHandler::SDCardInserted() { top_file = 0; + filelist.refresh(); auto cs = ScreenHandler.getCurrentScreen(); if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) ScreenHandler.GotoScreen(DGUSLCD_SCREEN_SDFILELIST); @@ -614,8 +615,10 @@ void DGUSScreenVariableHandler::HandleManualMove(DGUS_VP_Variable &var, void *va int16_t movevalue = swap16(*(uint16_t*)val_ptr); #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - const uint16_t choice = *(uint16_t*)var.memadr; - movevalue = movevalue > 0 ? choice : -choice; + if (movevalue) { + const uint16_t choice = *(uint16_t*)var.memadr; + movevalue = movevalue < 0 ? -choice : choice; + } #endif char axiscode; unsigned int speed = 1500; //FIXME: get default feedrate for manual moves, dont hardcode. diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp index 49d89948ba..4a51606314 100644 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp @@ -37,7 +37,7 @@ #include "../../../../ultralcd.h" #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - uint16_t distanceToMove = 0.1; + uint16_t distanceToMove = 10; #endif const uint16_t VPList_Boot[] PROGMEM = { diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp index 5fbb307ee8..b641ec9ec7 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp @@ -37,7 +37,7 @@ #include "../../../../ultralcd.h" #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - uint16_t distanceToMove = 0.1; + uint16_t distanceToMove = 10; #endif const uint16_t VPList_Boot[] PROGMEM = { diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp index 37b7335e67..81e8a32a7f 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp @@ -36,7 +36,7 @@ #include "../../../../ultralcd.h" #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - uint16_t distanceToMove = 0.1; + uint16_t distanceToMove = 10; #endif const uint16_t VPList_Boot[] PROGMEM = { From a794538c5417a38288c1af912f305755aec46894 Mon Sep 17 00:00:00 2001 From: George Fu Date: Wed, 25 Mar 2020 16:18:48 +0800 Subject: [PATCH 0190/1454] Homing backoff enhancements - Define homing bump as an array - Add pre and post homing backoff options - Consolidate homing config options --- Marlin/Configuration_adv.h | 34 +++++++++++-------- Marlin/src/inc/SanityCheck.h | 4 +++ Marlin/src/module/delta.cpp | 4 +-- Marlin/src/module/motion.cpp | 32 ++++++----------- Marlin/src/module/motion.h | 17 ++++++---- .../share/tests/SAMD51_grandcentral_m4-tests | 4 +-- buildroot/share/tests/mega1280-tests | 1 + 7 files changed, 50 insertions(+), 46 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 1e29a355ff..5b28441882 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -592,8 +592,7 @@ // Default x offset in duplication mode (typically set to half print bed width) #define DEFAULT_DUPLICATION_X_OFFSET 100 - -#endif // DUAL_X_CARRIAGE +#endif // Activate a solenoid on the active extruder with M380. Disable all with M381. // Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid. @@ -601,19 +600,24 @@ // @section homing -// Homing hits each endstop, retracts by these distances, then does a slower bump. -#define X_HOME_BUMP_MM 5 -#define Y_HOME_BUMP_MM 5 -#define Z_HOME_BUMP_MM 2 -#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) -//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially -//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing +/** + * Homing Procedure + * Homing (G28) does an indefinite move towards the endstops to establish + * the position of the toolhead relative to the workspace. + */ -// When G28 is called, this option will make Y home before X -//#define HOME_Y_BEFORE_X +//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing -// Enable this if X or Y can't home without homing the other axis first. -//#define CODEPENDENT_XY_HOMING +#define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump +#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) + +//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (mm) Backoff from endstops after homing + +//#define QUICK_HOME // If G28 contains XY do a diagonal move first +//#define HOME_Y_BEFORE_X // If G28 contains XY home Y before X +//#define CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first + +// @section bltouch #if ENABLED(BLTOUCH) /** @@ -682,6 +686,8 @@ #endif // BLTOUCH +// @section extras + /** * Z Steppers Auto-Alignment * Add the G34 command to align multiple Z steppers using a bed probe. @@ -2319,7 +2325,7 @@ * HIGHEST 255 -64 (Too sensitive => False positive) * LOWEST 0 63 (Too insensitive => No trigger) * - * It is recommended to set [XYZ]_HOME_BUMP_MM to 0. + * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * * SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only *** * Poll the driver through SPI to determine load when homing. diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index bc41e4612f..ab64c9a4f8 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -493,6 +493,10 @@ #error "ORIG_Ex_AUTO_FAN_PIN is now just Ex_AUTO_FAN_PIN. Make sure your pins are up to date." #elif defined(ORIG_CHAMBER_AUTO_FAN_PIN) #error "ORIG_CHAMBER_AUTO_FAN_PIN is now just CHAMBER_AUTO_FAN_PIN. Make sure your pins are up to date." +#elif defined(HOMING_BACKOFF_MM) + #error "HOMING_BACKOFF_MM is now HOMING_BACKOFF_POST_MM. Please update Configuration_adv.h." +#elif defined(X_HOME_BUMP_MM) || defined(Y_HOME_BUMP_MM) || defined(Z_HOME_BUMP_MM) + #error "[XYZ]_HOME_BUMP_MM is now HOMING_BUMP_MM. Please update Configuration_adv.h." #endif /** diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 8821236fd1..1f532767cc 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -280,8 +280,8 @@ void home_delta() { sync_plan_position(); - #if DISABLED(DELTA_HOME_TO_SAFE_ZONE) && defined(HOMING_BACKOFF_MM) - constexpr xyz_float_t endstop_backoff = HOMING_BACKOFF_MM; + #if DISABLED(DELTA_HOME_TO_SAFE_ZONE) && defined(HOMING_BACKOFF_POST_MM) + constexpr xyz_float_t endstop_backoff = HOMING_BACKOFF_POST_MM; if (endstop_backoff.z) { current_position.z -= ABS(endstop_backoff.z) * Z_HOME_DIR; line_to_current_position(homing_feedrate(Z_AXIS)); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 1cc0a04712..3c89b933d8 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -74,15 +74,6 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -#define XYZ_CONSTS(T, NAME, OPT) const PROGMEM XYZval NAME##_P = { X_##OPT, Y_##OPT, Z_##OPT } - -XYZ_CONSTS(float, base_min_pos, MIN_POS); -XYZ_CONSTS(float, base_max_pos, MAX_POS); -XYZ_CONSTS(float, base_home_pos, HOME_POS); -XYZ_CONSTS(float, max_length, MAX_LENGTH); -XYZ_CONSTS(float, home_bump_mm, HOME_BUMP_MM); -XYZ_CONSTS(signed char, home_dir, HOME_DIR); - /** * axis_homed * Flags that each linear axis was homed. @@ -1567,14 +1558,13 @@ void homeaxis(const AxisEnum axis) { if (axis == Z_AXIS && bltouch.deploy()) return; // The initial DEPLOY #endif - do_homing_move(axis, 1.5f * max_length( - #if ENABLED(DELTA) - Z_AXIS - #else - axis - #endif - ) * axis_home_dir - ); + #if DISABLED(DELTA) && defined(SENSORLESS_BACKOFF_MM) + const xy_float_t backoff = SENSORLESS_BACKOFF_MM; + if (((ENABLED(X_SENSORLESS) && axis == X_AXIS) || (ENABLED(Y_SENSORLESS) && axis == Y_AXIS)) && backoff[axis]) + do_homing_move(axis, -ABS(backoff[axis]) * axis_home_dir, homing_feedrate(axis)); + #endif + + do_homing_move(axis, 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir); #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) if (axis == Z_AXIS) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) @@ -1583,14 +1573,14 @@ void homeaxis(const AxisEnum axis) { // When homing Z with probe respect probe clearance const float bump = axis_home_dir * ( #if HOMING_Z_WITH_PROBE - (axis == Z_AXIS && (Z_HOME_BUMP_MM)) ? _MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_HOME_BUMP_MM) : + (axis == Z_AXIS && home_bump_mm(Z_AXIS)) ? _MAX(Z_CLEARANCE_BETWEEN_PROBES, home_bump_mm(Z_AXIS)) : #endif home_bump_mm(axis) ); // If a second homing move is configured... if (bump) { - // Move away from the endstop by the axis HOME_BUMP_MM + // Move away from the endstop by the axis HOMING_BUMP_MM if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move Away:"); do_homing_move(axis, -bump #if HOMING_Z_WITH_PROBE @@ -1785,8 +1775,8 @@ void homeaxis(const AxisEnum axis) { if (axis == Z_AXIS && probe.stow()) return; #endif - #if DISABLED(DELTA) && defined(HOMING_BACKOFF_MM) - const xyz_float_t endstop_backoff = HOMING_BACKOFF_MM; + #if DISABLED(DELTA) && defined(HOMING_BACKOFF_POST_MM) + const xyz_float_t endstop_backoff = HOMING_BACKOFF_POST_MM; if (endstop_backoff[axis]) { current_position[axis] -= ABS(endstop_backoff[axis]) * axis_home_dir; line_to_current_position( diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index e504f187f9..ee15205409 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -114,20 +114,25 @@ extern int16_t feedrate_percentage; extern float e_move_accumulator; #endif -FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float(p); } -FORCE_INLINE signed char pgm_read_any(const signed char *p) { return pgm_read_byte(p); } +inline float pgm_read_any(const float *p) { return pgm_read_float(p); } +inline signed char pgm_read_any(const signed char *p) { return pgm_read_byte(p); } #define XYZ_DEFS(T, NAME, OPT) \ - extern const XYZval NAME##_P; \ - FORCE_INLINE T NAME(AxisEnum axis) { return pgm_read_any(&NAME##_P[axis]); } - + inline T NAME(const AxisEnum axis) { \ + static const XYZval NAME##_P PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \ + return pgm_read_any(&NAME##_P[axis]); \ + } XYZ_DEFS(float, base_min_pos, MIN_POS); XYZ_DEFS(float, base_max_pos, MAX_POS); XYZ_DEFS(float, base_home_pos, HOME_POS); XYZ_DEFS(float, max_length, MAX_LENGTH); -XYZ_DEFS(float, home_bump_mm, HOME_BUMP_MM); XYZ_DEFS(signed char, home_dir, HOME_DIR); +inline float home_bump_mm(const AxisEnum axis) { + static const xyz_pos_t home_bump_mm_P PROGMEM = HOMING_BUMP_MM; + return pgm_read_any(&home_bump_mm_P[axis]); +} + #if HAS_WORKSPACE_OFFSET void update_workspace_offset(const AxisEnum axis); #else diff --git a/buildroot/share/tests/SAMD51_grandcentral_m4-tests b/buildroot/share/tests/SAMD51_grandcentral_m4-tests index f93ef3343f..3e47afe327 100644 --- a/buildroot/share/tests/SAMD51_grandcentral_m4-tests +++ b/buildroot/share/tests/SAMD51_grandcentral_m4-tests @@ -22,9 +22,7 @@ opt_set E0_DRIVER_TYPE TMC2209 opt_set RESTORE_LEVELING_AFTER_G28 false opt_set LCD_LANGUAGE it opt_set NUM_Z_STEPPER_DRIVERS 2 -opt_set X_HOME_BUMP_MM 0 -opt_set Y_HOME_BUMP_MM 0 -opt_set Z_HOME_BUMP_MM 0 +opt_set HOMING_BUMP_MM "{ 0, 0, 0 }" opt_set SDCARD_CONNECTION LCD opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \ FILAMENT_RUNOUT_SENSOR G26_MESH_VALIDATION MESH_EDIT_GFX_OVERLAY Z_SAFE_HOMING \ diff --git a/buildroot/share/tests/mega1280-tests b/buildroot/share/tests/mega1280-tests index c2d55a92e5..7f2872a0b4 100644 --- a/buildroot/share/tests/mega1280-tests +++ b/buildroot/share/tests/mega1280-tests @@ -18,6 +18,7 @@ set -e restore_configs opt_set LCD_LANGUAGE an opt_enable SPINDLE_FEATURE ULTIMAKERCONTROLLER LCD_BED_LEVELING \ + SENSORLESS_BACKOFF_MM HOMING_BACKOFF_POST_MM HOME_Y_BEFORE_X CODEPENDENT_XY_HOMING \ MESH_BED_LEVELING ENABLE_LEVELING_FADE_HEIGHT MESH_G28_REST_ORIGIN \ G26_MESH_VALIDATION MESH_EDIT_MENU GCODE_QUOTED_STRINGS exec_test $1 $2 "Spindle, MESH_BED_LEVELING, and LCD" From 360e07c90f8149cc4ff6d91082d9080ea8f3f474 Mon Sep 17 00:00:00 2001 From: djessup Date: Sat, 18 Apr 2020 00:02:21 +1000 Subject: [PATCH 0191/1454] Add USE_PROBE_FOR_Z_HOMING option (#17359) --- Marlin/Configuration.h | 10 ++++++---- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 12 +++++++++--- 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 09942ace0e..0b3d580530 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -824,12 +824,15 @@ // /** - * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - * - * Enable this option for a probe connected to the Z Min endstop pin. + * Enable this option for a probe connected to the Z-MIN pin. + * The probe replaces the Z-MIN endstop and is used for Z homing. + * (Automatically enables USE_PROBE_FOR_Z_HOMING.) */ #define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN +// Force the use of the probe for Z-axis homing +//#define USE_PROBE_FOR_Z_HOMING + /** * Z_MIN_PROBE_PIN * @@ -1335,7 +1338,6 @@ */ //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" - // @section homing // The center of the bed is at (X=0, Y=0) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index dd1f13fae0..7adb08a4e6 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -583,7 +583,7 @@ #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #define HAS_CUSTOM_PROBE_PIN 1 #endif - #if Z_HOME_DIR < 0 && !HAS_CUSTOM_PROBE_PIN + #if Z_HOME_DIR < 0 && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ab64c9a4f8..bcfeecc9f8 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1815,8 +1815,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Endstop Tests */ -#define _PLUG_UNUSED_TEST(AXIS,PLUG) (DISABLED(USE_##PLUG##MIN_PLUG, USE_##PLUG##MAX_PLUG) && !(ENABLED(AXIS##_DUAL_ENDSTOPS) && WITHIN(AXIS##2_USE_ENDSTOP, _##PLUG##MAX_, _##PLUG##MIN_))) -#define _AXIS_PLUG_UNUSED_TEST(AXIS) (_PLUG_UNUSED_TEST(AXIS,X) && _PLUG_UNUSED_TEST(AXIS,Y) && _PLUG_UNUSED_TEST(AXIS,Z)) +#define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \ + && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \ + && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) ) +#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z)) // At least 3 endstop plugs must be used #if _AXIS_PLUG_UNUSED_TEST(X) @@ -1841,8 +1843,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Enable USE_YMAX_PLUG when homing Y to MAX." #endif #endif -#if Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG) + +// Z homing direction and plug usage flags +#if Z_HOME_DIR < 0 && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) #error "Enable USE_ZMIN_PLUG when homing Z to MIN." +#elif Z_HOME_DIR > 0 && ENABLED(USE_PROBE_FOR_Z_HOMING) + #error "Z_HOME_DIR must be -1 when homing Z with the probe." #elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG) #error "Enable USE_ZMAX_PLUG when homing Z to MAX." #endif From f94ab84dac095ad57c9a465712ce66e625f303ff Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Apr 2020 09:10:41 -0500 Subject: [PATCH 0192/1454] Malyan M300 support (#17421) --- .github/workflows/test-builds.yml | 1 + Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 6 ++ Marlin/src/pins/stm32f0/pins_MALYAN_M300.h | 88 ++++++++++++++++++++++ buildroot/share/tests/malyan_M300-tests | 14 ++++ platformio.ini | 12 +++ 6 files changed, 122 insertions(+) create mode 100644 Marlin/src/pins/stm32f0/pins_MALYAN_M300.h create mode 100755 buildroot/share/tests/malyan_M300-tests diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index b92b015287..29105c4ddc 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -57,6 +57,7 @@ jobs: - mks_robin - ARMED - FYSETC_S6 + - malyan_M300 # Put lengthy tests last diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 132699b2d4..bbbd404b32 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -300,6 +300,7 @@ #define BOARD_GTM32_REV_B 4023 // STM32F103VET6 controller #define BOARD_MKS_ROBIN_E3D 4024 // MKS Robin E3D(STM32F103RCT6) #define BOARD_MKS_ROBIN_E3 4025 // MKS Robin E3(STM32F103RCT6) +#define BOARD_MALYAN_M300 4026 // STM32F070-based delta // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 42b3c4e4e2..98415e02aa 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -464,6 +464,12 @@ #elif MB(CNCONTROLS_15D) #include "sam/pins_CNCONTROLS_15D.h" // SAM3X8E env:DUE env:DUE_USB +// +// STM32 ARM Cortex-M0 +// +#elif MB(MALYAN_M300) + #include "stm32f0/pins_MALYAN_M300.h" // STM32F070 env:malyan_M300 + // // STM32 ARM Cortex-M3 // diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h new file mode 100644 index 0000000000..c9c87d49b9 --- /dev/null +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -0,0 +1,88 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#pragma once + +#if NONE(__STM32F1__, STM32F1xx, STM32F0xx) + #error "Oops! Select a 'Malyan M300' board in 'Tools > Board.'" +#endif + +#define BOARD_INFO_NAME "Malyan M300" + +// +// EEPROM Emulation +// +#define FLASH_EEPROM_EMULATION + +// +// SD CARD SPI +// +#define SDSS SS_PIN + +// +// Timers +// +#undef STEP_TIMER +#undef TEMP_TIMER +#define STEP_TIMER 6 +#define TEMP_TIMER 7 + +// +// Limit Switches +// +#define X_MAX_PIN PC13 +#define Y_MAX_PIN PC14 +#define Z_MAX_PIN PC15 +#define Z_MIN_PIN PB7 + +// +// Steppers +// +#define X_STEP_PIN PB14 +#define X_DIR_PIN PB13 +#define X_ENABLE_PIN PB10 + +#define Y_STEP_PIN PB12 +#define Y_DIR_PIN PB11 +#define Y_ENABLE_PIN PB10 + +#define Z_STEP_PIN PB2 +#define Z_DIR_PIN PB1 +#define Z_ENABLE_PIN PB10 + +#define E0_STEP_PIN PA7 +#define E0_DIR_PIN PA6 +#define E0_ENABLE_PIN PB0 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA0 // Analog Input (HOTEND0 thermistor) +#define TEMP_BED_PIN PA4 // Analog Input (BED thermistor) + +// +// Heaters / Fans +// +#define HEATER_0_PIN PA1 // HOTEND0 MOSFET +#define HEATER_BED_PIN PA5 // BED MOSFET + +#define AUTO_FAN_PIN PA8 diff --git a/buildroot/share/tests/malyan_M300-tests b/buildroot/share/tests/malyan_M300-tests new file mode 100755 index 0000000000..31cbabd754 --- /dev/null +++ b/buildroot/share/tests/malyan_M300-tests @@ -0,0 +1,14 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F070CB Malyan M300 +# + +# exit on first failure +set -e + +use_example_configs "delta/Malyan M300" +opt_disable AUTO_BED_LEVELING_3POINT +exec_test $1 $2 "Malyan M300 (delta)" + +# cleanup +restore_configs diff --git a/platformio.ini b/platformio.ini index 0828170e44..d4c56876fc 100644 --- a/platformio.ini +++ b/platformio.ini @@ -610,6 +610,18 @@ build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py -DMCU_STM32F103CB -D src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, LiquidCrystal, LiquidTWI2, TMCStepper, U8glib-HAL, SPI +# +# Malyan M300 (STM32F070CB) +# +[env:malyan_M300] +platform = ststm32@>=6.1.0 +board = malyanm300_f070cb +build_flags = ${common.build_flags} + -DUSBCON -DUSBD_VID=0x0483 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"MALYAN_M300\"" + -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED +src_filter = ${common.default_src_filter} + +lib_ignore = U8glib, LiquidCrystal_I2C, LiquidCrystal, NewliquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, Servo(STM32F1), TMC26XStepper, U8glib-HAL + # # Chitu boards like Tronxy X5s (STM32F103ZET6) # From 3a42b6c5c60b98d38f1acd353f5bbae4e15857e5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Apr 2020 10:24:20 -0500 Subject: [PATCH 0193/1454] Patch M425 for CAN_CALIBRATE Fixes #17430 --- Marlin/src/gcode/calibrate/G425.cpp | 3 +-- Marlin/src/gcode/calibrate/M425.cpp | 15 ++++++++++++--- Marlin/src/inc/Conditionals_post.h | 2 +- 3 files changed, 14 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 42c56fe51d..6ac3c70c48 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -51,7 +51,6 @@ #undef CALIBRATION_MEASURE_AT_TOP_EDGES #endif - /** * G425 backs away from the calibration object by various distances * depending on the confidence level: @@ -256,7 +255,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t #endif } - if (AXIS_CAN_CALIBRATE(X) && axis == X_AXIS || AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS) { + if ((AXIS_CAN_CALIBRATE(X) && axis == X_AXIS) || (AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS)) { // Move to safe distance to the side of the calibration object current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); calibration_move(); diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 980152a4b1..c2a57686cf 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -46,8 +46,17 @@ void GcodeSuite::M425() { bool noArgs = true; + auto axis_can_calibrate = [](const uint8_t a) { + switch (a) { + default: + case X_AXIS: return AXIS_CAN_CALIBRATE(X); + case Y_AXIS: return AXIS_CAN_CALIBRATE(Y); + case Z_AXIS: return AXIS_CAN_CALIBRATE(Z); + } + }; + LOOP_XYZ(a) { - if (CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) { + if (AXIS_CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; @@ -74,7 +83,7 @@ void GcodeSuite::M425() { SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); - LOOP_XYZ(a) if (CAN_CALIBRATE(a)) { + LOOP_XYZ(a) if (axis_can_calibrate(a)) { SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_EOL(); @@ -87,7 +96,7 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_XYZ(a) if (CAN_CALIBRATE(a) && backlash.has_measurement(AxisEnum(a))) { + LOOP_XYZ(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); } diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index b28b27792d..ee41c4af67 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -147,7 +147,7 @@ #define Z_AXIS_INDEX 2 #define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX) #else - #define CAN_CALIBRATE(...) 1 + #define CAN_CALIBRATE(A,B) 1 #endif #endif #define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) From d78ce58b6f3758900d34d8bd7b2de3e365c92ba1 Mon Sep 17 00:00:00 2001 From: android444 Date: Fri, 17 Apr 2020 17:46:04 +0200 Subject: [PATCH 0194/1454] Update a (c) date (#17584) Little update --- Marlin/Marlin.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin.ino b/Marlin/Marlin.ino index 6f8842cc0b..d1d58d483d 100644 --- a/Marlin/Marlin.ino +++ b/Marlin/Marlin.ino @@ -3,7 +3,7 @@ Marlin Firmware - (c) 2011-2019 MarlinFirmware + (c) 2011-2020 MarlinFirmware Portions of Marlin are (c) by their respective authors. All code complies with GPLv2 and/or GPLv3 From 50fa87f1cfad92ff88f7c14ecaa39e1c2b33639f Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Fri, 17 Apr 2020 18:19:31 +0200 Subject: [PATCH 0195/1454] Proportional Autotemp followup (#17585) Co-authored-by: Scott Lahteine --- Marlin/src/module/planner.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e053676574..f55ef37bc4 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2991,13 +2991,14 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { const int16_t target = thermalManager.degTargetHotend(active_extruder); autotemp_min = target + AUTOTEMP_MIN_P; autotemp_max = target + AUTOTEMP_MAX_P; - autotemp_factor = AUTOTEMP_FACTOR_P; #endif if (parser.seenval('S')) autotemp_min = parser.value_celsius(); if (parser.seenval('B')) autotemp_max = parser.value_celsius(); - if (parser.seenval('F')) autotemp_factor = parser.value_float(); - if (!autotemp_factor) autotemp_enabled = false; // F0 will disable autotemp - } + // When AUTOTEMP_PROPORTIONAL is enabled, F0 disables autotemp. + // Normally, leaving off F also disables autotemp. + autotemp_factor = parser.seen('F') ? parser.value_float() : TERN(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P, 0); + autotemp_enabled = autotemp_factor != 0; + } #endif From a12b021733bbc5228e9fb155dd08d5140bb9fd5b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 18 Apr 2020 00:03:23 +0000 Subject: [PATCH 0196/1454] [cron] Bump distribution date (2020-04-18) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4b8fa39992..86a3b661e1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-17" + #define STRING_DISTRIBUTION_DATE "2020-04-18" #endif /** From 8ad056013cd14907dc1a2aebdc0f4a31308606e2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Apr 2020 22:33:15 -0500 Subject: [PATCH 0197/1454] Define "resolution" in bits --- Marlin/src/module/thermistor/thermistors.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 8ac9f11a55..032386c2bd 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -23,8 +23,8 @@ #include "../../inc/MarlinConfig.h" -#define THERMISTOR_TABLE_ADC_RESOLUTION 1024 -#define THERMISTOR_TABLE_SCALE (HAL_ADC_RANGE / (THERMISTOR_TABLE_ADC_RESOLUTION)) +#define THERMISTOR_TABLE_ADC_RESOLUTION 10 +#define THERMISTOR_TABLE_SCALE (HAL_ADC_RANGE / _BV(THERMISTOR_TABLE_ADC_RESOLUTION)) #if ENABLED(HAL_ADC_FILTERED) #define OVERSAMPLENR 1 #else From 8e8ba46cb6eefbd9bc0ba2d7d8e6079ec1c5c75d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 19 Apr 2020 00:03:26 +0000 Subject: [PATCH 0198/1454] [cron] Bump distribution date (2020-04-19) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 86a3b661e1..c77b0792ef 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-18" + #define STRING_DISTRIBUTION_DATE "2020-04-19" #endif /** From 4a5a3d27ed29d7bab3de9b64b1a1728fd65c755f Mon Sep 17 00:00:00 2001 From: grauerfuchs <42082416+grauerfuchs@users.noreply.github.com> Date: Sat, 18 Apr 2020 23:56:23 -0400 Subject: [PATCH 0199/1454] Option to use raw digipot values (#17536) --- Marlin/Configuration_adv.h | 23 ++++--- Marlin/src/HAL/AVR/inc/SanityCheck.h | 10 --- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 2 +- Marlin/src/MarlinCore.cpp | 4 +- .../src/feature/digipot/digipot_mcp4018.cpp | 68 +++++++++---------- .../src/feature/digipot/digipot_mcp4451.cpp | 28 ++++---- .../src/gcode/feature/digipot/M907-M910.cpp | 8 +-- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/inc/Conditionals_adv.h | 4 ++ Marlin/src/inc/SanityCheck.h | 12 +++- Marlin/src/lcd/extui/ui_api.cpp | 2 +- buildroot/share/tests/mega2560-tests | 8 ++- 13 files changed, 89 insertions(+), 84 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5b28441882..ecc2cbf2d2 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -926,9 +926,20 @@ //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis -// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro) -//#define DIGIPOT_I2C -#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A) +/** + * I2C-based DIGIPOTs (e.g., Azteeg X3 Pro) + */ +//#define DIGIPOT_MCP4018 // Requires https://github.com/stawel/SlowSoftI2CMaster +//#define DIGIPOT_MCP4451 +#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) + #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5 + + // Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS. + // These correspond to the physical drivers, so be mindful if the order is changed. + #define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO + + //#define DIGIPOT_USE_RAW_VALUES // Use DIGIPOT_MOTOR_CURRENT raw wiper values (instead of A4988 motor currents) + /** * Common slave addresses: * @@ -943,12 +954,6 @@ #define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT #endif -//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster -#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8 MKS SBASE: 5 -// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS. -// These correspond to the physical drivers, so be mindful if the order is changed. -#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO - //=========================================================================== //=============================Additional Features=========================== //=========================================================================== diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 1c7c68f216..996cf52973 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -25,16 +25,6 @@ * Test AVR-specific configuration values for errors at compile-time. */ -/** - * Digipot requirement - */ - #if ENABLED(DIGIPOT_MCP4018) - #if !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \ - || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1) - #error "DIGIPOT_MCP4018 requires DIGIPOTS_I2C_SDA_* pins to be defined." - #endif -#endif - /** * Checks for FAST PWM */ diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 949c7f4899..2606ef26b5 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -174,7 +174,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o // // Flag any i2c pin conflicts // -#if ANY(DIGIPOT_I2C, DIGIPOT_MCP4018, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM) +#if ANY(HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM) #define USEDI2CDEV_M 1 // /Wire.cpp #if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 759d3b2132..b38ef9bfb1 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -70,7 +70,7 @@ #include "libs/buzzer.h" #endif -#if ENABLED(DIGIPOT_I2C) +#if HAS_I2C_DIGIPOT #include "feature/digipot/digipot.h" #endif @@ -1070,7 +1070,7 @@ void setup() { SETUP_RUN(enableStepperDrivers()); #endif - #if ENABLED(DIGIPOT_I2C) + #if HAS_I2C_DIGIPOT SETUP_RUN(digipot_i2c_init()); #endif diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index 675b3e38f0..40481caacf 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -22,53 +22,46 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(DIGIPOT_I2C, DIGIPOT_MCP4018) +#if ENABLED(DIGIPOT_MCP4018) #include -#include //https://github.com/stawel/SlowSoftI2CMaster +#include // https://github.com/stawel/SlowSoftI2CMaster // Settings for the I2C based DIGIPOT (MCP4018) based on WT150 #define DIGIPOT_A4988_Rsx 0.250 #define DIGIPOT_A4988_Vrefmax 1.666 -#define DIGIPOT_A4988_MAX_VALUE 127 +#define DIGIPOT_MCP4018_MAX_VALUE 127 -#define DIGIPOT_A4988_Itripmax(Vref) ((Vref)/(8.0*DIGIPOT_A4988_Rsx)) +#define DIGIPOT_A4988_Itripmax(Vref) ((Vref) / (8.0 * DIGIPOT_A4988_Rsx)) -#define DIGIPOT_A4988_FACTOR ((DIGIPOT_A4988_MAX_VALUE)/DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax)) +#define DIGIPOT_A4988_FACTOR ((DIGIPOT_MCP4018_MAX_VALUE) / DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax)) #define DIGIPOT_A4988_MAX_CURRENT 2.0 static byte current_to_wiper(const float current) { - const int16_t value = ceil(float(DIGIPOT_A4988_FACTOR) * current); - return byte(constrain(value, 0, DIGIPOT_A4988_MAX_VALUE)); + const int16_t value = TERN(DIGIPOT_USE_RAW_VALUES, current, CEIL(current * DIGIPOT_A4988_FACTOR)); + return byte(constrain(value, 0, DIGIPOT_MCP4018_MAX_VALUE)); } -const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = { - DIGIPOTS_I2C_SDA_X - #if DIGIPOT_I2C_NUM_CHANNELS > 1 - , DIGIPOTS_I2C_SDA_Y - #if DIGIPOT_I2C_NUM_CHANNELS > 2 - , DIGIPOTS_I2C_SDA_Z - #if DIGIPOT_I2C_NUM_CHANNELS > 3 - , DIGIPOTS_I2C_SDA_E0 - #if DIGIPOT_I2C_NUM_CHANNELS > 4 - , DIGIPOTS_I2C_SDA_E1 - #endif - #endif - #endif - #endif -}; - static SlowSoftI2CMaster pots[DIGIPOT_I2C_NUM_CHANNELS] = { - SlowSoftI2CMaster { sda_pins[X_AXIS], DIGIPOTS_I2C_SCL } + SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_X, DIGIPOTS_I2C_SCL) #if DIGIPOT_I2C_NUM_CHANNELS > 1 - , SlowSoftI2CMaster { sda_pins[Y_AXIS], DIGIPOTS_I2C_SCL } + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Y, DIGIPOTS_I2C_SCL) #if DIGIPOT_I2C_NUM_CHANNELS > 2 - , SlowSoftI2CMaster { sda_pins[Z_AXIS], DIGIPOTS_I2C_SCL } + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Z, DIGIPOTS_I2C_SCL) #if DIGIPOT_I2C_NUM_CHANNELS > 3 - , SlowSoftI2CMaster { sda_pins[E_AXIS], DIGIPOTS_I2C_SCL } + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E0, DIGIPOTS_I2C_SCL) #if DIGIPOT_I2C_NUM_CHANNELS > 4 - , SlowSoftI2CMaster { sda_pins[E_AXIS + 1], DIGIPOTS_I2C_SCL } + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E1, DIGIPOTS_I2C_SCL) + #if DIGIPOT_I2C_NUM_CHANNELS > 5 + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E2, DIGIPOTS_I2C_SCL) + #if DIGIPOT_I2C_NUM_CHANNELS > 6 + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E3, DIGIPOTS_I2C_SCL) + #if DIGIPOT_I2C_NUM_CHANNELS > 7 + , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E4, DIGIPOTS_I2C_SCL) + #endif + #endif + #endif #endif #endif #endif @@ -85,18 +78,23 @@ static void i2c_send(const uint8_t channel, const byte v) { // This is for the MCP4018 I2C based digipot void digipot_i2c_set_current(const uint8_t channel, const float current) { - i2c_send(channel, current_to_wiper(_MIN(_MAX(current, 0), float(DIGIPOT_A4988_MAX_CURRENT)))); + const float ival = _MIN(_MAX(current, 0), float(DIGIPOT_MCP4018_MAX_VALUE)); + i2c_send(channel, current_to_wiper(ival)); } void digipot_i2c_init() { - static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS; + LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init(); - LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) - pots[i].i2c_init(); - - // setup initial currents as defined in Configuration_adv.h + // Init currents according to Configuration_adv.h + static const float digipot_motor_current[] PROGMEM = + #if ENABLED(DIGIPOT_USE_RAW_VALUES) + DIGIPOT_MOTOR_CURRENT + #else + DIGIPOT_I2C_MOTOR_CURRENTS + #endif + ; LOOP_L_N(i, COUNT(digipot_motor_current)) digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } -#endif // DIGIPOT_I2C && DIGIPOT_MCP4018 +#endif // DIGIPOT_MCP4018 diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index 79bb6eb3c2..c3c49f2c8c 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(DIGIPOT_I2C) && DISABLED(DIGIPOT_MCP4018) +#if ENABLED(DIGIPOT_MCP4451) #include #include @@ -33,18 +33,18 @@ // Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro #if MB(5DPRINT) - #define DIGIPOT_I2C_FACTOR 117.96 - #define DIGIPOT_I2C_MAX_CURRENT 1.736 + #define DIGIPOT_I2C_FACTOR 117.96f + #define DIGIPOT_I2C_MAX_CURRENT 1.736f #elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) - #define DIGIPOT_I2C_FACTOR 113.5 - #define DIGIPOT_I2C_MAX_CURRENT 2.0 + #define DIGIPOT_I2C_FACTOR 113.5f + #define DIGIPOT_I2C_MAX_CURRENT 2.0f #else - #define DIGIPOT_I2C_FACTOR 106.7 - #define DIGIPOT_I2C_MAX_CURRENT 2.5 + #define DIGIPOT_I2C_FACTOR 106.7f + #define DIGIPOT_I2C_MAX_CURRENT 2.5f #endif static byte current_to_wiper(const float current) { - return byte(CEIL(float((DIGIPOT_I2C_FACTOR * current)))); + return byte(TERN(DIGIPOT_USE_RAW_VALUES, current, CEIL(DIGIPOT_I2C_FACTOR * current))); } static void digipot_i2c_send(const byte addr, const byte a, const byte b) { @@ -62,8 +62,8 @@ static void digipot_i2c_send(const byte addr, const byte a, const byte b) { // This is for the MCP4451 I2C based digipot void digipot_i2c_set_current(const uint8_t channel, const float current) { - // these addresses are specific to Azteeg X3 Pro, can be set to others, - // In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1 + // These addresses are specific to Azteeg X3 Pro, can be set to others. + // In this case first digipot is at address A0=0, A1=0, second one is at A0=0, A1=1 const byte addr = channel < 4 ? DIGIPOT_I2C_ADDRESS_A : DIGIPOT_I2C_ADDRESS_B; // channel 0-3 vs 4-7 // Initial setup @@ -77,14 +77,14 @@ void digipot_i2c_set_current(const uint8_t channel, const float current) { void digipot_i2c_init() { #if MB(MKS_SBASE) - configure_i2c(16); // Setting clock_option to 16 ensure the I2C bus is initialized at 400kHz + configure_i2c(16); // Set clock_option to 16 ensure I2C is initialized at 400kHz #else Wire.begin(); #endif - // setup initial currents as defined in Configuration_adv.h - static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS; + // Set up initial currents as defined in Configuration_adv.h + static const float digipot_motor_current[] PROGMEM = TERN(DIGIPOT_USE_RAW_VALUES, DIGIPOT_MOTOR_CURRENT, DIGIPOT_I2C_MOTOR_CURRENTS); LOOP_L_N(i, COUNT(digipot_motor_current)) digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } -#endif // DIGIPOT_I2C +#endif // DIGIPOT_MCP4451 diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index fe8e37ebdd..a61a4a1943 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT) +#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || ENABLED(DAC_STEPPER_CURRENT) #include "../../gcode.h" @@ -30,7 +30,7 @@ #include "../../../module/stepper.h" #endif -#if ENABLED(DIGIPOT_I2C) +#if HAS_I2C_DIGIPOT #include "../../../feature/digipot/digipot.h" #endif @@ -62,7 +62,7 @@ void GcodeSuite::M907() { #endif - #if ENABLED(DIGIPOT_I2C) + #if HAS_I2C_DIGIPOT // this one uses actual amps in floating point LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) digipot_i2c_set_current(i, parser.value_float()); // Additional extruders use B,C,D for channels 4,5,6. @@ -103,4 +103,4 @@ void GcodeSuite::M907() { #endif // DAC_STEPPER_CURRENT -#endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT || HAS_MOTOR_CURRENT_PWM || DIGIPOT_I2C +#endif // HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || DAC_STEPPER_CURRENT diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 57abc37b0d..dd2ede5d22 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -794,7 +794,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 900: M900(); break; // M900: Set advance K factor. #endif - #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT) + #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || ENABLED(DAC_STEPPER_CURRENT) case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes. #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) case 908: M908(); break; // M908: Control digital trimpot directly. diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 315b080e33..9df5002e6e 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -938,7 +938,7 @@ private: static void M918(); #endif - #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT) + #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || ENABLED(DAC_STEPPER_CURRENT) static void M907(); #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) static void M908(); diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 65dac5a004..66c3f5b632 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -113,6 +113,10 @@ #define HAS_LEDS_OFF_FLAG 1 #endif +#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) + #define HAS_I2C_DIGIPOT 1 +#endif + // Multiple Z steppers #ifndef NUM_Z_STEPPER_DRIVERS #define NUM_Z_STEPPER_DRIVERS 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index bcfeecc9f8..1b2f7fd2fb 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -497,6 +497,8 @@ #error "HOMING_BACKOFF_MM is now HOMING_BACKOFF_POST_MM. Please update Configuration_adv.h." #elif defined(X_HOME_BUMP_MM) || defined(Y_HOME_BUMP_MM) || defined(Z_HOME_BUMP_MM) #error "[XYZ]_HOME_BUMP_MM is now HOMING_BUMP_MM. Please update Configuration_adv.h." +#elif defined(DIGIPOT_I2C) + #error "DIGIPOT_I2C is now DIGIPOT_MCP4451 (or DIGIPOT_MCP4018). Please update Configuration_adv.h." #endif /** @@ -1587,6 +1589,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS // Pins are required for heaters #if ENABLED(HEATER_0_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS) #error "MAX6675_SS_PIN (required for TEMP_SENSOR_0) not defined for this board." +#elif HOTENDS && !HAS_TEMP_HOTEND + #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." #elif (HOTENDS > 1 || ENABLED(HEATERS_PARALLEL)) && !HAS_HEATER_1 #error "HEATER_1_PIN not defined for this board." #endif @@ -2443,10 +2447,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Digipot requirement */ -#if ENABLED(DIGIPOT_MCP4018) - #if !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \ +#if HAS_I2C_DIGIPOT + #if BOTH(DIGIPOT_MCP4018, DIGIPOT_MCP4451) + #error "Enable only one of DIGIPOT_MCP4018 or DIGIPOT_MCP4451." + #elif !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \ || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1) - #error "DIGIPOT_MCP4018 requires DIGIPOTS_I2C_SDA_* pins to be defined." + #error "DIGIPOT_MCP4018/4451 requires DIGIPOTS_I2C_SDA_* pins to be defined." #endif #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index ddb9cfc3bb..b5f94539fe 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -780,7 +780,7 @@ namespace ExtUI { */ int16_t mmToWholeSteps(const float mm, const axis_t axis) { const float steps = mm / planner.steps_to_mm[axis]; - return steps > 0 ? ceil(steps) : floor(steps); + return steps > 0 ? CEIL(steps) : FLOOR(steps); } #endif diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index 8c6c025aee..45dbcb9ffb 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -127,13 +127,15 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Cyrillic" # Test many less common options # restore_configs -opt_set MOTHERBOARD BOARD_MEGATRONICS_32 +opt_set MOTHERBOARD BOARD_MIGHTYBOARD_REVE +opt_set TEMP_SENSOR_0 -2 +opt_set DIGIPOT_I2C_NUM_CHANNELS 5 opt_set LCD_LANGUAGE it opt_set MIXING_STEPPERS 2 opt_set SERVO_DELAY "{ 300, 300, 300 }" opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY \ - REPRAP_DISCOUNT_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ FIX_MOUNTED_PROBE AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE FILAMENT_WIDTH_SENSOR \ Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ @@ -143,7 +145,7 @@ opt_set FAN_MIN_PWM 50 opt_set FAN_KICKSTART_TIME 100 opt_set XY_FREQUENCY_LIMIT 15 opt_add FILWIDTH_PIN 5 -exec_test $1 $2 "Megatronics 3.2 | Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." +exec_test $1 $2 "Mightyboard Rev. E | CoreXY, Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." ######## Other Standard LCD/Panels ############## # From b420fdaa87d0612877e4cb754f4662db09cbf0ce Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 18 Apr 2020 23:36:34 -0500 Subject: [PATCH 0200/1454] Digipots followup --- Marlin/Configuration_adv.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ecc2cbf2d2..05c629d853 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -950,8 +950,8 @@ * AZTEEG_X5_MINI_WIFI 0x58 0x5C MCP4451 * MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018 */ - #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT - #define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT + //#define DIGIPOT_I2C_ADDRESS_A 0x2C // Unshifted slave address for first DIGIPOT + //#define DIGIPOT_I2C_ADDRESS_B 0x2D // Unshifted slave address for second DIGIPOT #endif //=========================================================================== From ad7a6e10a7e8f2d56ed2f585b485a3900e7f5bcf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Apr 2020 00:56:43 -0500 Subject: [PATCH 0201/1454] Fix no-bed compile error --- Marlin/src/lcd/menu/menu_temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 01cf39d7b3..b00a3d964a 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -284,7 +284,7 @@ void menu_temperature() { // bool has_heat = false; HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } - #if HAS_TEMP_BED + #if HAS_HEATED_BED if (thermalManager.temp_bed.target) has_heat = true; #endif if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); From 87875e0de8fe2107642dce3cad0928504ed58d74 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Apr 2020 02:01:30 -0500 Subject: [PATCH 0202/1454] Fix mixing with "unload all" compile --- Marlin/src/feature/fwretract.cpp | 27 +++++--------------- Marlin/src/feature/mixing.cpp | 2 +- Marlin/src/feature/mixing.h | 12 +++------ Marlin/src/gcode/feature/pause/M701_M702.cpp | 10 +++++--- Marlin/src/inc/Conditionals_adv.h | 4 +++ Marlin/src/module/planner.cpp | 9 +++---- 6 files changed, 24 insertions(+), 40 deletions(-) diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 7d756ac6d0..122e9ae4f7 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -95,7 +95,7 @@ void FWRetract::reset() { */ void FWRetract::retract(const bool retracting #if EXTRUDERS > 1 - , bool swapping /* =false */ + , bool swapping/*=false*/ #endif ) { // Prevent two retracts or recovers in a row @@ -128,12 +128,8 @@ void FWRetract::retract(const bool retracting SERIAL_ECHOLNPAIR("current_hop ", current_hop); //*/ - const float base_retract = ( - (swapping ? settings.swap_retract_length : settings.retract_length) - #if ENABLED(RETRACT_SYNC_MIXING) - * (MIXING_STEPPERS) - #endif - ); + const float base_retract = TERN(RETRACT_SYNC_MIXING, MIXING_STEPPERS, 1) + * (swapping ? settings.swap_retract_length : settings.retract_length); // The current position will be the destination for E and Z moves destination = current_position; @@ -148,10 +144,7 @@ void FWRetract::retract(const bool retracting // Retract by moving from a faux E position back to the current E position current_retract[active_extruder] = base_retract; prepare_internal_move_to_destination( // set current to destination - settings.retract_feedrate_mm_s - #if ENABLED(RETRACT_SYNC_MIXING) - * (MIXING_STEPPERS) - #endif + settings.retract_feedrate_mm_s * TERN(RETRACT_SYNC_MIXING, MIXING_STEPPERS, 1) ); // Is a Z hop set, and has the hop not yet been done? @@ -177,18 +170,12 @@ void FWRetract::retract(const bool retracting current_retract[active_extruder] = 0; - const feedRate_t fr_mm_s = ( - (swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s) - #if ENABLED(RETRACT_SYNC_MIXING) - * (MIXING_STEPPERS) - #endif - ); + const feedRate_t fr_mm_s = TERN(RETRACT_SYNC_MIXING, MIXING_STEPPERS, 1) + * (swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s); prepare_internal_move_to_destination(fr_mm_s); // Recover E, set_current_to_destination } - #if ENABLED(RETRACT_SYNC_MIXING) - mixer.T(old_mixing_tool); // Restore original mixing tool - #endif + TERN_(RETRACT_SYNC_MIXING, mixer.T(old_mixing_tool)); // Restore original mixing tool retracted[active_extruder] = retracting; // Active extruder now retracted / recovered diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index d6ae2bb629..fe0f19d13e 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -115,7 +115,7 @@ void Mixer::init() { reset_vtools(); - #if ENABLED(RETRACT_SYNC_MIXING) + #if HAS_MIXER_SYNC_CHANNEL // AUTORETRACT_TOOL gets the same amount of all filaments MIXER_STEPPER_LOOP(i) color[MIXER_AUTORETRACT_TOOL][i] = COLOR_A_MASK; diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index da5240995c..156870b659 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -52,25 +52,19 @@ enum MixTool { LAST_USER_VIRTUAL_TOOL = MIXING_VIRTUAL_TOOLS - 1, NR_USER_VIRTUAL_TOOLS, MIXER_DIRECT_SET_TOOL = NR_USER_VIRTUAL_TOOLS, - #if ENABLED(RETRACT_SYNC_MIXING) + #if HAS_MIXER_SYNC_CHANNEL MIXER_AUTORETRACT_TOOL, #endif NR_MIXING_VIRTUAL_TOOLS }; -#if ENABLED(RETRACT_SYNC_MIXING) - #define MAX_VTOOLS 254 -#else - #define MAX_VTOOLS 255 -#endif +#define MAX_VTOOLS TERN(HAS_MIXER_SYNC_CHANNEL, 254, 255) static_assert(NR_MIXING_VIRTUAL_TOOLS <= MAX_VTOOLS, "MIXING_VIRTUAL_TOOLS must be <= " STRINGIFY(MAX_VTOOLS) "!"); -#define MIXER_STEPPER_LOOP(VAR) \ - for (uint_fast8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++) - #define MIXER_BLOCK_FIELD mixer_comp_t b_color[MIXING_STEPPERS] #define MIXER_POPULATE_BLOCK() mixer.populate_block(block->b_color) #define MIXER_STEPPER_SETUP() mixer.stepper_setup(current_block->b_color) +#define MIXER_STEPPER_LOOP(VAR) for (uint_fast8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++) #if ENABLED(GRADIENT_MIX) diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index aa3c3c4c30..9f89f2dab7 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -163,16 +163,18 @@ void GcodeSuite::M702() { #if ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) float mix_multiplier = 1.0; - if (!parser.seenval('T')) { + const bool seenT = parser.seenval('T'); + if (!seenT) { mixer.T(MIXER_AUTORETRACT_TOOL); mix_multiplier = MIXING_STEPPERS; } - else + #else + constexpr bool seenT = true; #endif - { + + if (seenT) { const int8_t target_e_stepper = get_target_e_stepper_from_command(); if (target_e_stepper < 0) return; - mixer.T(MIXER_DIRECT_SET_TOOL); MIXER_STEPPER_LOOP(i) mixer.set_collector(i, (i == (uint8_t)target_e_stepper) ? 1.0 : 0.0); mixer.normalize(); diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 66c3f5b632..56c7ce7463 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -56,6 +56,10 @@ #undef SHOW_TEMP_ADC_VALUES #endif +#if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) + #define HAS_MIXER_SYNC_CHANNEL 1 +#endif + #if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) #define HAS_DUPLICATION_MODE 1 #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index f55ef37bc4..b7e2681141 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2133,17 +2133,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if EXTRUDERS { current_speed.e = steps_dist_mm.e * inverse_secs; - #if BOTH(MIXING_EXTRUDER, RETRACT_SYNC_MIXING) + #if HAS_MIXER_SYNC_CHANNEL // Move all mixing extruders at the specified rate if (mixer.get_current_vtool() == MIXER_AUTORETRACT_TOOL) current_speed.e *= MIXING_STEPPERS; #endif const feedRate_t cs = ABS(current_speed.e), - max_fr = (settings.max_feedrate_mm_s[E_AXIS_N(extruder)] - #if BOTH(MIXING_EXTRUDER, RETRACT_SYNC_MIXING) - * MIXING_STEPPERS - #endif - ); + max_fr = settings.max_feedrate_mm_s[E_AXIS_N(extruder)] + * TERN(HAS_MIXER_SYNC_CHANNEL, MIXING_STEPPERS, 1); if (cs > max_fr) NOMORE(speed_factor, max_fr / cs); } #endif From 1bbd77646e4400f556eb916acf829a5f626a13d1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Apr 2020 02:37:33 -0500 Subject: [PATCH 0203/1454] Clean up language files --- Marlin/src/lcd/language/language_ca.h | 35 ++++----- Marlin/src/lcd/language/language_nl.h | 33 +++------ Marlin/src/lcd/language/language_pl.h | 29 -------- Marlin/src/lcd/language/language_zh_TW.h | 94 +----------------------- 4 files changed, 26 insertions(+), 165 deletions(-) diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 66b061c6ab..70966ca4cd 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -56,21 +56,20 @@ namespace Language_ca { PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Estableix origen"); PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preescalfa ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preescalfa ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" End"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" End ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Tot"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Llit"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Conf."); + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" End"); + PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" End ~"); + PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Tot"); + PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Llit"); + PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Conf."); PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Preescalfa ") PREHEAT_2_LABEL; PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Preescalfa ") PREHEAT_2_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" End"); - PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" End ~"); - PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Tot"); - PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Llit"); - PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Conf."); + PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Preescalfa ") PREHEAT_2_LABEL _UxGT(" End"); + PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Preescalfa ") PREHEAT_2_LABEL _UxGT(" End ~"); + PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preescalfa ") PREHEAT_2_LABEL _UxGT(" Tot"); + PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preescalfa ") PREHEAT_2_LABEL _UxGT(" Llit"); + PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preescalfa ") PREHEAT_2_LABEL _UxGT(" Conf."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Refreda"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Switch power on"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Switch power off"); + PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudeix"); PROGMEM Language_Str MSG_RETRACT = _UxGT("Retreu"); PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mou eixos"); @@ -98,11 +97,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_FLOW = _UxGT("Flux"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flux ~"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VViatge min"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Accel. max ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Accel. max ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Accel. max ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Accel. max ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Accel. max *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Accel. retracc"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Accel. Viatge"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passos/mm"); @@ -204,11 +199,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Font alimentacio"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Força motor"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Repren impressió"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora incorrecta"); diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 5742d15ef1..9bc88cffb8 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -46,13 +46,9 @@ namespace Language_nl { PROGMEM Language_Str MSG_MAIN = _UxGT("Hoofdmenu"); PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autostart"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motoren uit"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); //accepted English terms + PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); // accepted English terms PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Vooruitgang Test"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Homing XYZ"); + PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klik voor begin"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Volgende Plaats"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Bed level kompl."); @@ -115,8 +111,8 @@ namespace Language_nl { PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatuur"); PROGMEM Language_Str MSG_MOTION = _UxGT("Beweging"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); //accepted english dutch - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); //accepted english dutch + PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); // accepted english dutch + PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); // accepted english dutch PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); @@ -139,7 +135,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Geen beweging."); PROGMEM Language_Str MSG_KILLED = _UxGT("Afgebroken. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("Gestopt. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retract mm"); //accepted English term in Dutch + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retract mm"); // accepted English term in Dutch PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Ruil Retract mm"); PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retract F"); PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); @@ -155,7 +151,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Zelf-Test"); PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Home %s%s%s Eerst"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z Offset"); //accepted English term in Dutch + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z Offset"); // accepted English term in Dutch PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystap X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystap Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystap Z"); @@ -183,14 +179,6 @@ namespace Language_nl { PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibratie"); PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Zet Delta Hoogte"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Printer Stats"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Board Info"); //accepted English term in Dutch - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistors"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruders"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Over Printer"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Printer Info"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocol"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case licht"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Onjuiste printer"); @@ -211,16 +199,13 @@ namespace Language_nl { PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); //accepted English term in Dutch + PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); // accepted English term in Dutch PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Motorstroom"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); //accepted English term in Dutch - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); //accepted English term in Dutch - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); //accepted English term in Dutch - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); //accepted English term in Dutch + PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC Opslaan"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Hervat print"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); //accepeted English term + PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); // accepted English term // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index cd3fbe0da9..d263726e13 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -507,21 +507,6 @@ namespace Language_pl { PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Odwrotny gradient"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-tool"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" End V-tool"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" End Z:"); - - PROGMEM Language_Str MSG_GAMES = _UxGT("Games"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); - PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); // // Filament Change screens show up to 3 lines on a 4-line display @@ -552,18 +537,4 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver Current"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorless Homing"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" in:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); - PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; - PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; - PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); } diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 0c6f69ebba..274d692776 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -251,18 +251,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("自動控溫"); //"Autotemp" PROGMEM Language_Str MSG_LCD_ON = _UxGT("開 "); //"On" PROGMEM Language_Str MSG_LCD_OFF = _UxGT("關 "); //"Off" - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); - PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); //"PID-P" - PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); - PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); //"PID-I" - PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); - PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); //"PID-D" - PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); - PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); //"PID-C" - PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); - PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); //"PID-F" - PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); + PROGMEM Language_Str MSG_SELECT = _UxGT("選擇"); //"Select" PROGMEM Language_Str MSG_SELECT_E = _UxGT("選擇 *"); PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); //"Accel" acceleration @@ -271,7 +260,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_VB_JERK = _UxGT("軸抖動速率") LCD_STR_B; //"Vb-jerk" PROGMEM Language_Str MSG_VC_JERK = _UxGT("軸抖動速率") LCD_STR_C; //"Vc-jerk" PROGMEM Language_Str MSG_VE_JERK = _UxGT("擠出機抖動速率"); //"Ve-jerk" - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + PROGMEM Language_Str MSG_VELOCITY = _UxGT("速度"); // "Velocity" PROGMEM Language_Str MSG_VMAX_A = _UxGT("最大進料速率") LCD_STR_A; //"Vmax " max_feedrate_mm_s PROGMEM Language_Str MSG_VMAX_B = _UxGT("最大進料速率") LCD_STR_B; @@ -374,26 +363,12 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("釋放媒體"); //"Release Media" PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z探針在熱床之外"); //"Z probe out. bed" Z probe is not within the physical limits PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("偏斜因數"); // "Skew Factor" - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); // "BLTouch" + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch 自檢"); // "BLTouch Self-Test" PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("重置BLTouch"); // "Reset BLTouch" PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("裝載BLTouch"); // "Stow BLTouch" PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("部署BLTouch"); // "Deploy BLTouch" - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Cmd: SW-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Cmd: 5V-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Cmd: OD-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Cmd: Mode-Store"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("DANGER: Bad settings can cause damage! Proceed anyway?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Save"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("歸位 %s%s%s 先"); //"Home ... first" PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("探針偏移"); //Probe Offsets PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("探針X偏移量"); //Probe X Offset @@ -500,52 +475,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: 太冷"); // "M600: Too cold" - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Resume Print"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resuming..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Load Filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Load All"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Load to Nozzle"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Eject Filament"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Eject Filament ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Unload Filament"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Loading Fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejecting Fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Unloading Fil...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("All"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reset MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetting MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Remove, click"); - - PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Component ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mixer"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Full Gradient"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Toggle Mix"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Reverse Gradient"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-tool"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" End V-tool"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" End Z:"); - - PROGMEM Language_Str MSG_GAMES = _UxGT("Games"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); - PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display @@ -575,21 +504,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成..")); //"Click to finish" PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢復中 ...")); //"Resuming..." #endif // LCD_HEIGHT < 4 - - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver Current"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorless Homing"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" in:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); - PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; - PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; - PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); } #if FAN_COUNT == 1 From 776d7761d954074154666bdb169d10ff1bbbf196 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 20 Apr 2020 00:03:17 +0000 Subject: [PATCH 0204/1454] [cron] Bump distribution date (2020-04-20) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c77b0792ef..2c3f6e4eb7 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-19" + #define STRING_DISTRIBUTION_DATE "2020-04-20" #endif /** From 78fe411c7d75131eb9868de0311a519688ca9633 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 20 Apr 2020 00:01:14 -0500 Subject: [PATCH 0205/1454] Include swt_init in log --- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 2 +- Marlin/src/MarlinCore.cpp | 2 +- .../extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 1c20e7f652..a8a7279ffb 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -209,7 +209,7 @@ } -#endif // ENABLED(LPC_SOFTWARE_SPI) +#endif // LPC_SOFTWARE_SPI void SPIClass::begin() { spiBegin(); } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index b38ef9bfb1..1b78d45a01 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1154,7 +1154,7 @@ void setup() { #endif #if ENABLED(SWITCHING_TOOLHEAD) - swt_init(); + SETUP_RUN(swt_init()); #endif #if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index c8cc6e8e9d..59af72edaa 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -507,7 +507,7 @@ bool UIFlashStorage::is_present = false; } #else return VERIFY_ERROR; - #endif // ENABLED(SDSUPPORT) + #endif // SDSUPPORT } bool UIFlashStorage::BootMediaReader::isAvailable(uint32_t slot) { From 5d0deba938eaaa47c2fc27fdb296499698006f87 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Apr 2020 23:37:05 -0500 Subject: [PATCH 0206/1454] Longer default power-up delay See MarlinFirmware/Configurations#78 --- Marlin/Configuration.h | 2 +- Marlin/src/feature/power.cpp | 8 +++----- Marlin/src/gcode/control/M80_M81.cpp | 9 ++++----- 3 files changed, 8 insertions(+), 11 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 0b3d580530..2804d8ffef 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -326,7 +326,7 @@ #define PSU_ACTIVE_HIGH false // Set 'false' for ATX, 'true' for X-Box //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 - //#define PSU_POWERUP_DELAY 100 // (ms) Delay for the PSU to warm up to full power + //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power //#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin #if ENABLED(AUTO_POWER_CONTROL) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 510747d208..746ce6aa3d 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -107,11 +107,9 @@ void Power::power_on() { lastPowerOn = millis(); if (!powersupply_on) { PSU_PIN_ON(); - - #if HAS_TRINAMIC_CONFIG - delay(PSU_POWERUP_DELAY); // Wait for power to settle - restore_stepper_drivers(); - #endif + delay(PSU_POWERUP_DELAY); + restore_stepper_drivers(); + TERN_(HAS_TRINAMIC_CONFIG, delay(PSU_POWERUP_DELAY)); } } diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index e8d9aa2fdf..a5ff7d05d9 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -72,16 +72,15 @@ #endif #if DISABLED(AUTO_POWER_CONTROL) - delay(PSU_POWERUP_DELAY); // Wait for power to settle + delay(PSU_POWERUP_DELAY); restore_stepper_drivers(); + TERN_(HAS_TRINAMIC_CONFIG, delay(PSU_POWERUP_DELAY)); #endif - #if HAS_LCD_MENU - ui.reset_status(); - #endif + TERN_(HAS_LCD_MENU, ui.reset_status()); } -#endif // ENABLED(PSU_CONTROL) +#endif // PSU_CONTROL /** * M81: Turn off Power, including Power Supply, if there is one. From 15f6f53638a6778d22a17e1900fb3a9fdc92dade Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Apr 2020 23:56:55 -0500 Subject: [PATCH 0207/1454] Add HAS_HOTEND, etc. --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/feature/powerloss.cpp | 6 +- Marlin/src/feature/powerloss.h | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 +- Marlin/src/gcode/calibrate/G28.cpp | 6 +- Marlin/src/gcode/calibrate/G33.cpp | 2 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 6 +- Marlin/src/gcode/calibrate/G425.cpp | 8 +- Marlin/src/inc/Conditionals_LCD.h | 12 +- Marlin/src/inc/Conditionals_post.h | 590 +++++++++++++----- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 16 +- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 6 +- .../lcd/dogm/status_screen_lite_ST7920.cpp | 10 +- .../screens/advanced_settings_menu.cpp | 4 +- .../screens/bio_advanced_settings.cpp | 4 +- .../screens/change_filament_screen.cpp | 4 +- .../screens/nozzle_offsets_screen.cpp | 2 +- .../screens/nudge_nozzle_screen.cpp | 2 +- .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 2 +- .../lib/ftdi_eve_touch_ui/screens/screens.h | 2 +- .../screens/temperature_screen.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 8 +- Marlin/src/lcd/menu/menu.h | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 6 +- Marlin/src/lcd/menu/menu_temperature.cpp | 12 +- Marlin/src/lcd/menu/menu_tune.cpp | 2 +- Marlin/src/module/configuration_store.cpp | 2 +- Marlin/src/module/temperature.cpp | 54 +- Marlin/src/module/temperature.h | 6 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 2 +- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 2 +- Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 2 +- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h | 2 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 2 +- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 4 +- Marlin/src/pins/sensitive_pins.h | 6 +- 38 files changed, 554 insertions(+), 256 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index d451f7246f..86a08afbff 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -38,7 +38,7 @@ #include "../../../gcode/gcode.h" #include "../../../libs/least_squares_fit.h" - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #include "../../../module/tool_change.h" #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 37d82eec6a..77d0047a5c 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -366,11 +366,11 @@ void PrintJobRecovery::resume() { #endif // Restore all hotend temperatures - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() { const int16_t et = info.target_temperature[e]; if (et) { - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND sprintf_P(cmd, PSTR("T%i"), e); gcode.process_subcommands_now(cmd); #endif @@ -517,7 +517,7 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPAIR("active_extruder: ", int(info.active_extruder)); #endif - #if HOTENDS + #if HAS_HOTEND DEBUG_ECHOPGM("target_temperature: "); HOTEND_LOOP() { DEBUG_ECHO(info.target_temperature[e]); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 0496560785..34a26b6eb9 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -68,7 +68,7 @@ typedef struct { #endif #endif - #if HOTENDS + #if HAS_HOTEND int16_t target_temperature[HOTENDS]; #endif diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index de69545983..f316b4a7a1 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -60,7 +60,7 @@ #include "../../../lcd/extui/ui_api.h" #endif -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND #include "../../../module/tool_change.h" #endif @@ -283,7 +283,7 @@ G29_TYPE GcodeSuite::G29() { */ if (!g29_in_progress) { - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND if (active_extruder != 0) tool_change(0); #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 3437e33942..8c699b5fd3 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -27,7 +27,7 @@ #include "../../module/stepper.h" #include "../../module/endstops.h" -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND #include "../../module/tool_change.h" #endif @@ -285,7 +285,7 @@ void GcodeSuite::G28() { #endif // Always home with tool 0 active - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #if DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE) const uint8_t old_tool_index = active_extruder; #endif @@ -474,7 +474,7 @@ void GcodeSuite::G28() { restore_feedrate_and_scaling(); // Restore the active tool after homing - #if HOTENDS > 1 && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)) + #if HAS_MULTI_HOTEND && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)) tool_change(old_tool_index, NONE(PARKING_EXTRUDER, DUAL_X_CARRIAGE)); // Do move if one of these #endif diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index ac2cdf7d4d..6f0f8a5562 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -35,7 +35,7 @@ #include "../../module/probe.h" #endif -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND #include "../../module/tool_change.h" #endif diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index d1b828d079..091619c6ff 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -32,7 +32,7 @@ #include "../../module/motion.h" #include "../../module/probe.h" -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND #include "../../module/tool_change.h" #endif @@ -124,7 +124,7 @@ void GcodeSuite::G34() { #endif // Always home with tool 0 active - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND const uint8_t old_tool_index = active_extruder; tool_change(0, true); #endif @@ -386,7 +386,7 @@ void GcodeSuite::G34() { #endif // Restore the active tool after homing - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous tool for parking extruder #endif diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 6ac3c70c48..b9dcc8f284 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -126,7 +126,7 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { calibration_move(); } -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND inline void set_nozzle(measurements_t &m, const uint8_t extruder) { if (extruder != active_extruder) { park_above_object(m, CALIBRATION_MEASUREMENT_UNKNOWN); @@ -505,7 +505,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND set_nozzle(m, extruder); #else UNUSED(extruder); @@ -548,7 +548,7 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty) normalize_hotend_offsets(); #endif - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND set_nozzle(m, 0); #endif } @@ -582,7 +582,7 @@ inline void calibrate_all() { #endif // Cycle the toolheads so the servos settle into their "natural" positions - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND HOTEND_LOOP() set_nozzle(m, e); #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 7adb08a4e6..ac44e832d6 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -466,6 +466,14 @@ #define E_MANUAL EXTRUDERS #endif +#if HOTENDS + #define HAS_HOTEND 1 + #if HOTENDS > 1 + #define HAS_MULTI_HOTEND 1 + #define HAS_HOTEND_OFFSET 1 + #endif +#endif + // Helper macros for extruder and hotend arrays #define HOTEND_LOOP() for (int8_t e = 0; e < HOTENDS; e++) #define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) @@ -481,10 +489,6 @@ #define SWITCHING_NOZZLE_TWO_SERVOS 1 #endif -#if HOTENDS > 1 - #define HAS_HOTEND_OFFSET 1 -#endif - /** * Default hotend offsets, if not defined */ diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ee41c4af67..48490b75a5 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -386,7 +386,7 @@ #endif #if !defined(PSU_POWERUP_DELAY) && ENABLED(PSU_CONTROL) - #define PSU_POWERUP_DELAY 100 + #define PSU_POWERUP_DELAY 250 #endif /** @@ -1255,94 +1255,238 @@ */ // Steppers -#define HAS_X_ENABLE (PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X))) -#define HAS_X_DIR (PIN_EXISTS(X_DIR)) -#define HAS_X_STEP (PIN_EXISTS(X_STEP)) -#define HAS_X_MICROSTEPS (PIN_EXISTS(X_MS1)) +#if PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X)) + #define HAS_X_ENABLE 1 +#endif +#if PIN_EXISTS(X_DIR) + #define HAS_X_DIR 1 +#endif +#if PIN_EXISTS(X_STEP) + #define HAS_X_STEP 1 +#endif +#if PIN_EXISTS(X_MS1) + #define HAS_X_MICROSTEPS 1 +#endif -#define HAS_X2_ENABLE (PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2))) -#define HAS_X2_DIR (PIN_EXISTS(X2_DIR)) -#define HAS_X2_STEP (PIN_EXISTS(X2_STEP)) -#define HAS_X2_MICROSTEPS (PIN_EXISTS(X2_MS1)) +#if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)) + #define HAS_X2_ENABLE 1 +#endif +#if PIN_EXISTS(X2_DIR) + #define HAS_X2_DIR 1 +#endif +#if PIN_EXISTS(X2_STEP) + #define HAS_X2_STEP 1 +#endif +#if PIN_EXISTS(X2_MS1) + #define HAS_X2_MICROSTEPS 1 +#endif -#define HAS_Y_ENABLE (PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))) -#define HAS_Y_DIR (PIN_EXISTS(Y_DIR)) -#define HAS_Y_STEP (PIN_EXISTS(Y_STEP)) -#define HAS_Y_MICROSTEPS (PIN_EXISTS(Y_MS1)) +#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) + #define HAS_Y_ENABLE 1 +#endif +#if PIN_EXISTS(Y_DIR) + #define HAS_Y_DIR 1 +#endif +#if PIN_EXISTS(Y_STEP) + #define HAS_Y_STEP 1 +#endif +#if PIN_EXISTS(Y_MS1) + #define HAS_Y_MICROSTEPS 1 +#endif -#define HAS_Y2_ENABLE (PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))) -#define HAS_Y2_DIR (PIN_EXISTS(Y2_DIR)) -#define HAS_Y2_STEP (PIN_EXISTS(Y2_STEP)) -#define HAS_Y2_MICROSTEPS (PIN_EXISTS(Y2_MS1)) +#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) + #define HAS_Y2_ENABLE 1 +#endif +#if PIN_EXISTS(Y2_DIR) + #define HAS_Y2_DIR 1 +#endif +#if PIN_EXISTS(Y2_STEP) + #define HAS_Y2_STEP 1 +#endif +#if PIN_EXISTS(Y2_MS1) + #define HAS_Y2_MICROSTEPS 1 +#endif -#define HAS_Z_ENABLE (PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))) -#define HAS_Z_DIR (PIN_EXISTS(Z_DIR)) -#define HAS_Z_STEP (PIN_EXISTS(Z_STEP)) -#define HAS_Z_MICROSTEPS (PIN_EXISTS(Z_MS1)) +#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) + #define HAS_Z_ENABLE 1 +#endif +#if PIN_EXISTS(Z_DIR) + #define HAS_Z_DIR 1 +#endif +#if PIN_EXISTS(Z_STEP) + #define HAS_Z_STEP 1 +#endif +#if PIN_EXISTS(Z_MS1) + #define HAS_Z_MICROSTEPS 1 +#endif -#define HAS_Z2_ENABLE (PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))) -#define HAS_Z2_DIR (PIN_EXISTS(Z2_DIR)) -#define HAS_Z2_STEP (PIN_EXISTS(Z2_STEP)) -#define HAS_Z2_MICROSTEPS (PIN_EXISTS(Z2_MS1)) +#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) + #define HAS_Z2_ENABLE 1 +#endif +#if PIN_EXISTS(Z2_DIR) + #define HAS_Z2_DIR 1 +#endif +#if PIN_EXISTS(Z2_STEP) + #define HAS_Z2_STEP 1 +#endif +#if PIN_EXISTS(Z2_MS1) + #define HAS_Z2_MICROSTEPS 1 +#endif -#define HAS_Z3_ENABLE (PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))) -#define HAS_Z3_DIR (PIN_EXISTS(Z3_DIR)) -#define HAS_Z3_STEP (PIN_EXISTS(Z3_STEP)) -#define HAS_Z3_MICROSTEPS (PIN_EXISTS(Z3_MS1)) +#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) + #define HAS_Z3_ENABLE 1 +#endif +#if PIN_EXISTS(Z3_DIR) + #define HAS_Z3_DIR 1 +#endif +#if PIN_EXISTS(Z3_STEP) + #define HAS_Z3_STEP 1 +#endif +#if PIN_EXISTS(Z3_MS1) + #define HAS_Z3_MICROSTEPS 1 +#endif -#define HAS_Z4_ENABLE (PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))) -#define HAS_Z4_DIR (PIN_EXISTS(Z4_DIR)) -#define HAS_Z4_STEP (PIN_EXISTS(Z4_STEP)) -#define HAS_Z4_MICROSTEPS (PIN_EXISTS(Z4_MS1)) +#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) + #define HAS_Z4_ENABLE 1 +#endif +#if PIN_EXISTS(Z4_DIR) + #define HAS_Z4_DIR 1 +#endif +#if PIN_EXISTS(Z4_STEP) + #define HAS_Z4_STEP 1 +#endif +#if PIN_EXISTS(Z4_MS1) + #define HAS_Z4_MICROSTEPS 1 +#endif // Extruder steppers and solenoids -#define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0))) -#define HAS_E0_DIR (PIN_EXISTS(E0_DIR)) -#define HAS_E0_STEP (PIN_EXISTS(E0_STEP)) -#define HAS_E0_MICROSTEPS (PIN_EXISTS(E0_MS1)) -#define HAS_SOLENOID_0 (PIN_EXISTS(SOL0)) +#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) + #define HAS_E0_ENABLE 1 +#endif +#if PIN_EXISTS(E0_DIR) + #define HAS_E0_DIR 1 +#endif +#if PIN_EXISTS(E0_STEP) + #define HAS_E0_STEP 1 +#endif +#if PIN_EXISTS(E0_MS1) + #define HAS_E0_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL0) + #define HAS_SOLENOID_0 1 +#endif -#define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1))) -#define HAS_E1_DIR (PIN_EXISTS(E1_DIR)) -#define HAS_E1_STEP (PIN_EXISTS(E1_STEP)) -#define HAS_E1_MICROSTEPS (PIN_EXISTS(E1_MS1)) -#define HAS_SOLENOID_1 (PIN_EXISTS(SOL1)) +#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) + #define HAS_E1_ENABLE 1 +#endif +#if PIN_EXISTS(E1_DIR) + #define HAS_E1_DIR 1 +#endif +#if PIN_EXISTS(E1_STEP) + #define HAS_E1_STEP 1 +#endif +#if PIN_EXISTS(E1_MS1) + #define HAS_E1_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL1) + #define HAS_SOLENOID_1 1 +#endif -#define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2))) -#define HAS_E2_DIR (PIN_EXISTS(E2_DIR)) -#define HAS_E2_STEP (PIN_EXISTS(E2_STEP)) -#define HAS_E2_MICROSTEPS (PIN_EXISTS(E2_MS1)) -#define HAS_SOLENOID_2 (PIN_EXISTS(SOL2)) +#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) + #define HAS_E2_ENABLE 1 +#endif +#if PIN_EXISTS(E2_DIR) + #define HAS_E2_DIR 1 +#endif +#if PIN_EXISTS(E2_STEP) + #define HAS_E2_STEP 1 +#endif +#if PIN_EXISTS(E2_MS1) + #define HAS_E2_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL2) + #define HAS_SOLENOID_2 1 +#endif -#define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3))) -#define HAS_E3_DIR (PIN_EXISTS(E3_DIR)) -#define HAS_E3_STEP (PIN_EXISTS(E3_STEP)) -#define HAS_E3_MICROSTEPS (PIN_EXISTS(E3_MS1)) -#define HAS_SOLENOID_3 (PIN_EXISTS(SOL3)) +#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) + #define HAS_E3_ENABLE 1 +#endif +#if PIN_EXISTS(E3_DIR) + #define HAS_E3_DIR 1 +#endif +#if PIN_EXISTS(E3_STEP) + #define HAS_E3_STEP 1 +#endif +#if PIN_EXISTS(E3_MS1) + #define HAS_E3_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL3) + #define HAS_SOLENOID_3 1 +#endif -#define HAS_E4_ENABLE (PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4))) -#define HAS_E4_DIR (PIN_EXISTS(E4_DIR)) -#define HAS_E4_STEP (PIN_EXISTS(E4_STEP)) -#define HAS_E4_MICROSTEPS (PIN_EXISTS(E4_MS1)) -#define HAS_SOLENOID_4 (PIN_EXISTS(SOL4)) +#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) + #define HAS_E4_ENABLE 1 +#endif +#if PIN_EXISTS(E4_DIR) + #define HAS_E4_DIR 1 +#endif +#if PIN_EXISTS(E4_STEP) + #define HAS_E4_STEP 1 +#endif +#if PIN_EXISTS(E4_MS1) + #define HAS_E4_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL4) + #define HAS_SOLENOID_4 1 +#endif -#define HAS_E5_ENABLE (PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5))) -#define HAS_E5_DIR (PIN_EXISTS(E5_DIR)) -#define HAS_E5_STEP (PIN_EXISTS(E5_STEP)) -#define HAS_E5_MICROSTEPS (PIN_EXISTS(E5_MS1)) -#define HAS_SOLENOID_5 (PIN_EXISTS(SOL5)) +#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) + #define HAS_E5_ENABLE 1 +#endif +#if PIN_EXISTS(E5_DIR) + #define HAS_E5_DIR 1 +#endif +#if PIN_EXISTS(E5_STEP) + #define HAS_E5_STEP 1 +#endif +#if PIN_EXISTS(E5_MS1) + #define HAS_E5_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL5) + #define HAS_SOLENOID_5 1 +#endif -#define HAS_E6_ENABLE (PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6))) -#define HAS_E6_DIR (PIN_EXISTS(E6_DIR)) -#define HAS_E6_STEP (PIN_EXISTS(E6_STEP)) -#define HAS_E6_MICROSTEPS (PIN_EXISTS(E6_MS1)) -#define HAS_SOLENOID_6 (PIN_EXISTS(SOL6)) +#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) + #define HAS_E6_ENABLE 1 +#endif +#if PIN_EXISTS(E6_DIR) + #define HAS_E6_DIR 1 +#endif +#if PIN_EXISTS(E6_STEP) + #define HAS_E6_STEP 1 +#endif +#if PIN_EXISTS(E6_MS1) + #define HAS_E6_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL6) + #define HAS_SOLENOID_6 1 +#endif -#define HAS_E7_ENABLE (PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7))) -#define HAS_E7_DIR (PIN_EXISTS(E7_DIR)) -#define HAS_E7_STEP (PIN_EXISTS(E7_STEP)) -#define HAS_E7_MICROSTEPS (PIN_EXISTS(E7_MS1)) -#define HAS_SOLENOID_7 (PIN_EXISTS(SOL7)) +#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) + #define HAS_E7_ENABLE 1 +#endif +#if PIN_EXISTS(E7_DIR) + #define HAS_E7_DIR 1 +#endif +#if PIN_EXISTS(E7_STEP) + #define HAS_E7_STEP 1 +#endif +#if PIN_EXISTS(E7_MS1) + #define HAS_E7_MICROSTEPS 1 +#endif +#if PIN_EXISTS(SOL7) + #define HAS_SOLENOID_7 1 +#endif // Trinamic Stepper Drivers #if HAS_TRINAMIC_CONFIG @@ -1405,62 +1549,146 @@ #define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_) #define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M)) -#define HAS_X_MIN _HAS_STOP(X,MIN) -#define HAS_X_MAX _HAS_STOP(X,MAX) -#define HAS_Y_MIN _HAS_STOP(Y,MIN) -#define HAS_Y_MAX _HAS_STOP(Y,MAX) -#define HAS_Z_MIN _HAS_STOP(Z,MIN) -#define HAS_Z_MAX _HAS_STOP(Z,MAX) -#define HAS_X2_MIN (PIN_EXISTS(X2_MIN)) -#define HAS_X2_MAX (PIN_EXISTS(X2_MAX)) -#define HAS_Y2_MIN (PIN_EXISTS(Y2_MIN)) -#define HAS_Y2_MAX (PIN_EXISTS(Y2_MAX)) -#define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN)) -#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX)) -#define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN)) -#define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX)) -#define HAS_Z4_MIN (PIN_EXISTS(Z4_MIN)) -#define HAS_Z4_MAX (PIN_EXISTS(Z4_MAX)) -#define HAS_Z_MIN_PROBE_PIN (HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE)) +#if _HAS_STOP(X,MIN) + #define HAS_X_MIN 1 +#endif +#if _HAS_STOP(X,MAX) + #define HAS_X_MAX 1 +#endif +#if _HAS_STOP(Y,MIN) + #define HAS_Y_MIN 1 +#endif +#if _HAS_STOP(Y,MAX) + #define HAS_Y_MAX 1 +#endif +#if _HAS_STOP(Z,MIN) + #define HAS_Z_MIN 1 +#endif +#if _HAS_STOP(Z,MAX) + #define HAS_Z_MAX 1 +#endif +#if PIN_EXISTS(X2_MIN) + #define HAS_X2_MIN 1 +#endif +#if PIN_EXISTS(X2_MAX) + #define HAS_X2_MAX 1 +#endif +#if PIN_EXISTS(Y2_MIN) + #define HAS_Y2_MIN 1 +#endif +#if PIN_EXISTS(Y2_MAX) + #define HAS_Y2_MAX 1 +#endif +#if PIN_EXISTS(Z2_MIN) + #define HAS_Z2_MIN 1 +#endif +#if PIN_EXISTS(Z2_MAX) + #define HAS_Z2_MAX 1 +#endif +#if PIN_EXISTS(Z3_MIN) + #define HAS_Z3_MIN 1 +#endif +#if PIN_EXISTS(Z3_MAX) + #define HAS_Z3_MAX 1 +#endif +#if PIN_EXISTS(Z4_MIN) + #define HAS_Z4_MIN 1 +#endif +#if PIN_EXISTS(Z4_MAX) + #define HAS_Z4_MAX 1 +#endif +#if HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE) + #define HAS_Z_MIN_PROBE_PIN 1 +#endif // // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface) // #define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && DISABLED(HEATER_##P##_USES_MAX6675)) -#define HAS_TEMP_ADC_0 HAS_ADC_TEST(0) -#define HAS_TEMP_ADC_1 HAS_ADC_TEST(1) -#define HAS_TEMP_ADC_2 HAS_ADC_TEST(2) -#define HAS_TEMP_ADC_3 HAS_ADC_TEST(3) -#define HAS_TEMP_ADC_4 HAS_ADC_TEST(4) -#define HAS_TEMP_ADC_5 HAS_ADC_TEST(5) -#define HAS_TEMP_ADC_6 HAS_ADC_TEST(6) -#define HAS_TEMP_ADC_7 HAS_ADC_TEST(7) -#define HAS_TEMP_ADC_BED HAS_ADC_TEST(BED) -#define HAS_TEMP_ADC_PROBE HAS_ADC_TEST(PROBE) -#define HAS_TEMP_ADC_CHAMBER HAS_ADC_TEST(CHAMBER) +#if HAS_ADC_TEST(0) + #define HAS_TEMP_ADC_0 1 +#endif +#if HAS_ADC_TEST(1) + #define HAS_TEMP_ADC_1 1 +#endif +#if HAS_ADC_TEST(2) + #define HAS_TEMP_ADC_2 1 +#endif +#if HAS_ADC_TEST(3) + #define HAS_TEMP_ADC_3 1 +#endif +#if HAS_ADC_TEST(4) + #define HAS_TEMP_ADC_4 1 +#endif +#if HAS_ADC_TEST(5) + #define HAS_TEMP_ADC_5 1 +#endif +#if HAS_ADC_TEST(6) + #define HAS_TEMP_ADC_6 1 +#endif +#if HAS_ADC_TEST(7) + #define HAS_TEMP_ADC_7 1 +#endif +#if HAS_ADC_TEST(BED) + #define HAS_TEMP_ADC_BED 1 +#endif +#if HAS_ADC_TEST(PROBE) + #define HAS_TEMP_ADC_PROBE 1 +#endif +#if HAS_ADC_TEST(CHAMBER) + #define HAS_TEMP_ADC_CHAMBER 1 +#endif -#define HAS_TEMP_HOTEND ((HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675)) && HOTENDS) +#if HOTENDS && (HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675)) + #define HAS_TEMP_HOTEND 1 +#endif #define HAS_TEMP_BED HAS_TEMP_ADC_BED #define HAS_TEMP_PROBE HAS_TEMP_ADC_PROBE #define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER #if ENABLED(JOYSTICK) - #define HAS_JOY_ADC_X PIN_EXISTS(JOY_X) - #define HAS_JOY_ADC_Y PIN_EXISTS(JOY_Y) - #define HAS_JOY_ADC_Z PIN_EXISTS(JOY_Z) - #define HAS_JOY_ADC_EN PIN_EXISTS(JOY_EN) + #if PIN_EXISTS(JOY_X) + #define HAS_JOY_ADC_X 1 +#endif + #if PIN_EXISTS(JOY_Y) + #define HAS_JOY_ADC_Y 1 +#endif + #if PIN_EXISTS(JOY_Z) + #define HAS_JOY_ADC_Z 1 +#endif + #if PIN_EXISTS(JOY_EN) + #define HAS_JOY_ADC_EN 1 +#endif #endif // Heaters -#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0)) -#define HAS_HEATER_1 (PIN_EXISTS(HEATER_1)) -#define HAS_HEATER_2 (PIN_EXISTS(HEATER_2)) -#define HAS_HEATER_3 (PIN_EXISTS(HEATER_3)) -#define HAS_HEATER_4 (PIN_EXISTS(HEATER_4)) -#define HAS_HEATER_5 (PIN_EXISTS(HEATER_5)) -#define HAS_HEATER_6 (PIN_EXISTS(HEATER_6)) -#define HAS_HEATER_7 (PIN_EXISTS(HEATER_7)) -#define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED)) +#if PIN_EXISTS(HEATER_0) + #define HAS_HEATER_0 1 +#endif +#if PIN_EXISTS(HEATER_1) + #define HAS_HEATER_1 1 +#endif +#if PIN_EXISTS(HEATER_2) + #define HAS_HEATER_2 1 +#endif +#if PIN_EXISTS(HEATER_3) + #define HAS_HEATER_3 1 +#endif +#if PIN_EXISTS(HEATER_4) + #define HAS_HEATER_4 1 +#endif +#if PIN_EXISTS(HEATER_5) + #define HAS_HEATER_5 1 +#endif +#if PIN_EXISTS(HEATER_6) + #define HAS_HEATER_6 1 +#endif +#if PIN_EXISTS(HEATER_7) + #define HAS_HEATER_7 1 +#endif +#if PIN_EXISTS(HEATER_BED) + #define HAS_HEATER_BED 1 +#endif // Shorthand for common combinations #if HAS_TEMP_BED && HAS_HEATER_BED @@ -1507,15 +1735,33 @@ #endif // Auto fans -#define HAS_AUTO_FAN_0 (HOTENDS > 0 && PIN_EXISTS(E0_AUTO_FAN)) -#define HAS_AUTO_FAN_1 (HOTENDS > 1 && PIN_EXISTS(E1_AUTO_FAN)) -#define HAS_AUTO_FAN_2 (HOTENDS > 2 && PIN_EXISTS(E2_AUTO_FAN)) -#define HAS_AUTO_FAN_3 (HOTENDS > 3 && PIN_EXISTS(E3_AUTO_FAN)) -#define HAS_AUTO_FAN_4 (HOTENDS > 4 && PIN_EXISTS(E4_AUTO_FAN)) -#define HAS_AUTO_FAN_5 (HOTENDS > 5 && PIN_EXISTS(E5_AUTO_FAN)) -#define HAS_AUTO_FAN_6 (HOTENDS > 6 && PIN_EXISTS(E6_AUTO_FAN)) -#define HAS_AUTO_FAN_7 (HOTENDS > 7 && PIN_EXISTS(E7_AUTO_FAN)) -#define HAS_AUTO_CHAMBER_FAN (HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_AUTO_FAN)) +#if HAS_HOTEND && PIN_EXISTS(E0_AUTO_FAN) + #define HAS_AUTO_FAN_0 1 +#endif +#if HOTENDS > 1 && PIN_EXISTS(E1_AUTO_FAN) + #define HAS_AUTO_FAN_1 1 +#endif +#if HOTENDS > 2 && PIN_EXISTS(E2_AUTO_FAN) + #define HAS_AUTO_FAN_2 1 +#endif +#if HOTENDS > 3 && PIN_EXISTS(E3_AUTO_FAN) + #define HAS_AUTO_FAN_3 1 +#endif +#if HOTENDS > 4 && PIN_EXISTS(E4_AUTO_FAN) + #define HAS_AUTO_FAN_4 1 +#endif +#if HOTENDS > 5 && PIN_EXISTS(E5_AUTO_FAN) + #define HAS_AUTO_FAN_5 1 +#endif +#if HOTENDS > 6 && PIN_EXISTS(E6_AUTO_FAN) + #define HAS_AUTO_FAN_6 1 +#endif +#if HOTENDS > 7 && PIN_EXISTS(E7_AUTO_FAN) + #define HAS_AUTO_FAN_7 1 +#endif +#if HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_AUTO_FAN) + #define HAS_AUTO_CHAMBER_FAN 1 +#endif #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN) #define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN) @@ -1535,24 +1781,52 @@ // Other fans #define HAS_FAN0 (PIN_EXISTS(FAN)) #define _HAS_FAN(P) (PIN_EXISTS(FAN##P) && CONTROLLER_FAN_PIN != FAN##P##_PIN && E0_AUTO_FAN_PIN != FAN##P##_PIN && E1_AUTO_FAN_PIN != FAN##P##_PIN && E2_AUTO_FAN_PIN != FAN##P##_PIN && E3_AUTO_FAN_PIN != FAN##P##_PIN && E4_AUTO_FAN_PIN != FAN##P##_PIN && E5_AUTO_FAN_PIN != FAN##P##_PIN && E6_AUTO_FAN_PIN != FAN##P##_PIN && E7_AUTO_FAN_PIN != FAN##P##_PIN) -#define HAS_FAN1 _HAS_FAN(1) -#define HAS_FAN2 _HAS_FAN(2) -#define HAS_FAN3 _HAS_FAN(3) -#define HAS_FAN4 _HAS_FAN(4) -#define HAS_FAN5 _HAS_FAN(5) -#define HAS_FAN6 _HAS_FAN(6) -#define HAS_FAN7 _HAS_FAN(7) -#define HAS_CONTROLLER_FAN (PIN_EXISTS(CONTROLLER_FAN)) +#if _HAS_FAN(1) + #define HAS_FAN1 1 +#endif +#if _HAS_FAN(2) + #define HAS_FAN2 1 +#endif +#if _HAS_FAN(3) + #define HAS_FAN3 1 +#endif +#if _HAS_FAN(4) + #define HAS_FAN4 1 +#endif +#if _HAS_FAN(5) + #define HAS_FAN5 1 +#endif +#if _HAS_FAN(6) + #define HAS_FAN6 1 +#endif +#if _HAS_FAN(7) + #define HAS_FAN7 1 +#endif +#if PIN_EXISTS(CONTROLLER_FAN) + #define HAS_CONTROLLER_FAN 1 +#endif // Servos -#define HAS_SERVO_0 (PIN_EXISTS(SERVO0) && NUM_SERVOS > 0) -#define HAS_SERVO_1 (PIN_EXISTS(SERVO1) && NUM_SERVOS > 1) -#define HAS_SERVO_2 (PIN_EXISTS(SERVO2) && NUM_SERVOS > 2) -#define HAS_SERVO_3 (PIN_EXISTS(SERVO3) && NUM_SERVOS > 3) -#define HAS_SERVOS (NUM_SERVOS > 0) +#if PIN_EXISTS(SERVO0) && NUM_SERVOS > 0 + #define HAS_SERVO_0 1 +#endif +#if PIN_EXISTS(SERVO1) && NUM_SERVOS > 1 + #define HAS_SERVO_1 1 +#endif +#if PIN_EXISTS(SERVO2) && NUM_SERVOS > 2 + #define HAS_SERVO_2 1 +#endif +#if PIN_EXISTS(SERVO3) && NUM_SERVOS > 3 + #define HAS_SERVO_3 1 +#endif +#if NUM_SERVOS > 0 + #define HAS_SERVOS 1 +#endif // Sensors -#define HAS_FILAMENT_WIDTH_SENSOR (PIN_EXISTS(FILWIDTH)) +#if PIN_EXISTS(FILWIDTH) + #define HAS_FILAMENT_WIDTH_SENSOR 1 +#endif // User Interface #if PIN_EXISTS(HOME) @@ -1638,14 +1912,30 @@ #endif #endif - #define HAS_MICROSTEP1 defined(MICROSTEP1) - #define HAS_MICROSTEP2 defined(MICROSTEP2) - #define HAS_MICROSTEP4 defined(MICROSTEP4) - #define HAS_MICROSTEP8 defined(MICROSTEP8) - #define HAS_MICROSTEP16 defined(MICROSTEP16) - #define HAS_MICROSTEP32 defined(MICROSTEP32) - #define HAS_MICROSTEP64 defined(MICROSTEP64) - #define HAS_MICROSTEP128 defined(MICROSTEP128) + #ifdef MICROSTEP1 + #define HAS_MICROSTEP1 1 + #endif + #ifdef MICROSTEP2 + #define HAS_MICROSTEP2 1 + #endif + #ifdef MICROSTEP4 + #define HAS_MICROSTEP4 1 + #endif + #ifdef MICROSTEP8 + #define HAS_MICROSTEP8 1 + #endif + #ifdef MICROSTEP16 + #define HAS_MICROSTEP16 1 + #endif + #ifdef MICROSTEP32 + #define HAS_MICROSTEP32 1 + #endif + #ifdef MICROSTEP64 + #define HAS_MICROSTEP64 1 + #endif + #ifdef MICROSTEP128 + #define HAS_MICROSTEP128 1 + #endif #endif // HAS_MICROSTEPS @@ -1896,8 +2186,12 @@ #undef NO_FAN_SLOWING_IN_PID_TUNING #endif -#define QUIET_PROBING (HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0)) -#define HEATER_IDLE_HANDLER EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) +#if HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) + #define QUIET_PROBING 1 +#endif +#if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) + #define HEATER_IDLE_HANDLER 1 +#endif #if ENABLED(ADVANCED_PAUSE_FEATURE) && !defined(FILAMENT_CHANGE_SLOW_LOAD_LENGTH) #define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 1b2f7fd2fb..fd81f8e4f6 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1591,11 +1591,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "MAX6675_SS_PIN (required for TEMP_SENSOR_0) not defined for this board." #elif HOTENDS && !HAS_TEMP_HOTEND #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." -#elif (HOTENDS > 1 || ENABLED(HEATERS_PARALLEL)) && !HAS_HEATER_1 +#elif (HAS_MULTI_HOTEND || ENABLED(HEATERS_PARALLEL)) && !HAS_HEATER_1 #error "HEATER_1_PIN not defined for this board." #endif -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND #if ENABLED(HEATER_1_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS2) #error "MAX6675_SS2_PIN (required for TEMP_SENSOR_1) not defined for this board." #elif TEMP_SENSOR_1 == 0 diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 3c89d1803c..905a72b053 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -745,7 +745,7 @@ void MarlinUI::draw_status_screen() { // // Hotend 1 or Bed Temperature // - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND lcd_moveto(8, 0); _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); #elif HAS_HEATED_BED @@ -763,7 +763,7 @@ void MarlinUI::draw_status_screen() { // // Hotend 1 or Bed Temperature // - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND lcd_moveto(10, 0); _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); #elif HAS_HEATED_BED @@ -791,7 +791,7 @@ void MarlinUI::draw_status_screen() { // If the first line has two extruder temps, // show more temperatures on the next line - #if HOTENDS > 2 || (HOTENDS > 1 && HAS_HEATED_BED) + #if HOTENDS > 2 || (HAS_MULTI_HOTEND && HAS_HEATED_BED) #if HOTENDS > 2 _draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink); @@ -924,7 +924,7 @@ void MarlinUI::draw_status_screen() { lcd_moveto(LCD_WIDTH - 9, 0); _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); - #if HAS_LEVELING && (HOTENDS > 1 || !HAS_HEATED_BED) + #if HAS_LEVELING && (HAS_MULTI_HOTEND || !HAS_HEATED_BED) lcd_put_wchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' '); #endif @@ -934,7 +934,7 @@ void MarlinUI::draw_status_screen() { // Hotend 1 or Bed Temperature // lcd_moveto(0, 1); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND _draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink); #elif HAS_HEATED_BED _draw_bed_status(blink); @@ -952,7 +952,7 @@ void MarlinUI::draw_status_screen() { lcd_moveto(0, 2); #if HOTENDS > 2 _draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink); - #elif HOTENDS > 1 && HAS_HEATED_BED + #elif HAS_MULTI_HOTEND && HAS_HEATED_BED _draw_bed_status(blink); #elif HAS_PRINT_PROGRESS #define DREW_PRINT_PROGRESS @@ -1077,7 +1077,7 @@ void MarlinUI::draw_status_screen() { if (thermalManager.degTargetBed() > 0) leds |= LED_A; #endif - #if HOTENDS + #if HAS_HOTEND if (thermalManager.degTargetHotend(0) > 0) leds |= LED_B; #endif @@ -1110,7 +1110,7 @@ void MarlinUI::draw_status_screen() { ) leds |= LED_C; #endif // FAN_COUNT > 0 - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND if (thermalManager.degTargetHotend(1) > 0) leds |= LED_C; #endif diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 8295e9e058..741f07330f 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -278,7 +278,7 @@ // // Status Screen Hotends bitmaps // - #if HOTENDS + #if HAS_HOTEND #define STATUS_HOTEND1_WIDTH 16 @@ -1343,7 +1343,7 @@ #undef STATUS_LOGO_WIDTH #endif - #if (HOTENDS > 1 && STATUS_LOGO_WIDTH && BED_OR_CHAMBER_OR_FAN) || (HOTENDS >= 3 && !BED_OR_CHAMBER_OR_FAN) + #if (HAS_MULTI_HOTEND && STATUS_LOGO_WIDTH && BED_OR_CHAMBER_OR_FAN) || (HOTENDS >= 3 && !BED_OR_CHAMBER_OR_FAN) #define _STATUS_HEATERS_X(H,S,N) ((LCD_PIXEL_WIDTH - (H * (S + N)) - (_EXTRA_WIDTH) + (STATUS_LOGO_WIDTH)) / 2) #if STATUS_HOTEND1_WIDTH #if HOTENDS > 2 @@ -1474,7 +1474,7 @@ constexpr uint8_t status_hotend_x[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_X, STATUS_HOTEND2_X, STATUS_HOTEND3_X, STATUS_HOTEND4_X, STATUS_HOTEND5_X, STATUS_HOTEND6_X); #define STATUS_HOTEND_X(N) status_hotend_x[N] - #elif HOTENDS > 1 + #elif HAS_MULTI_HOTEND #define STATUS_HOTEND_X(N) ((N) ? STATUS_HOTEND2_X : STATUS_HOTEND1_X) #else #define STATUS_HOTEND_X(N) STATUS_HOTEND1_X diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index e623776b31..64c6711fe8 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -431,7 +431,7 @@ void ST7920_Lite_Status_Screen::draw_static_elements() { // Draw the static icons in GDRAM draw_gdram_icon(0, 0, nozzle_icon); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND draw_gdram_icon(0, 1, nozzle_icon); draw_gdram_icon(0, 2, bed_icon); #else @@ -584,7 +584,7 @@ void ST7920_Lite_Status_Screen::draw_extruder_2_temp(const int16_t temp, const i #if HAS_HEATED_BED void ST7920_Lite_Status_Screen::draw_bed_temp(const int16_t temp, const int16_t target, bool forceUpdate) { const bool show_target = target && FAR(temp, target); - draw_temps(HOTENDS > 1 ? 2 : 1, temp, target, show_target, display_state.bed_show_target != show_target || forceUpdate); + draw_temps(HAS_MULTI_HOTEND ? 2 : 1, temp, target, show_target, display_state.bed_show_target != show_target || forceUpdate); display_state.bed_show_target = show_target; } #endif @@ -704,7 +704,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { const uint16_t feedrate_perc = feedrate_percentage; const uint16_t fs = thermalManager.scaledFanSpeed(0); const int16_t extruder_1_target = thermalManager.degTargetHotend(0); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND const int16_t extruder_2_target = thermalManager.degTargetHotend(1); #endif #if HAS_HEATED_BED @@ -731,7 +731,7 @@ void ST7920_Lite_Status_Screen::update_indicators(const bool forceUpdate) { const uint16_t feedrate_perc = feedrate_percentage; const int16_t extruder_1_temp = thermalManager.degHotend(0), extruder_1_target = thermalManager.degTargetHotend(0); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND const int16_t extruder_2_temp = thermalManager.degHotend(1), extruder_2_target = thermalManager.degTargetHotend(1); #endif @@ -741,7 +741,7 @@ void ST7920_Lite_Status_Screen::update_indicators(const bool forceUpdate) { #endif draw_extruder_1_temp(extruder_1_temp, extruder_1_target, forceUpdate); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND draw_extruder_2_temp(extruder_2_temp, extruder_2_target, forceUpdate); #endif #if HAS_HEATED_BED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index c5f69504d4..e625325d44 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -115,7 +115,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { ) .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled( - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND 1 #endif ) @@ -157,7 +157,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(ZOffsetScreen); break; #endif case 3: GOTO_SCREEN(StepsScreen); break; - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND case 4: GOTO_SCREEN(NozzleOffsetScreen); break; #endif case 5: GOTO_SCREEN(MaxVelocityScreen); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index ed8bcee557..d2c5c6658c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -58,7 +58,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(4) .button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) .tag(5) .button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) .enabled( - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND 1 #endif ) @@ -105,7 +105,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 4: GOTO_SCREEN(StepperBumpSensitivityScreen); break; #endif case 5: GOTO_SCREEN(EndstopStatesScreen); break; - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND case 6: GOTO_SCREEN(NozzleOffsetScreen); break; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp index 2b5963fdf6..a013949814 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp @@ -172,8 +172,8 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { const bool tog3 = screen_data.ChangeFilamentScreen.t_tag == 3; const bool tog4 = screen_data.ChangeFilamentScreen.t_tag == 4; const bool tog10 = screen_data.ChangeFilamentScreen.e_tag == 10; - #if HOTENDS > 1 - const bool tog11 = screen_data.ChangeFilamentScreen.e_tag == 11; + #if HAS_MULTI_HOTEND + const bool tog11 = screen_data.ChangeFilamentScreen.e_tag == 11; #endif #ifdef TOUCH_UI_PORTRAIT diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp index ae224e9c11..9ac402e197 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HOTENDS > 1 +#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_MULTI_HOTEND #include "screens.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp index d9910ffa04..0865b8ccbc 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp @@ -72,7 +72,7 @@ void NudgeNozzleScreen::onRedraw(draw_mode_t what) { w.text_field(0, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), str); #endif - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND format_position(str, getNozzleOffset_mm(X, E1), getNozzleOffset_mm(Y, E1), getNozzleOffset_mm(Z, E1)); w.text_field(0, GET_TEXT_F(MSG_OFFSETS_MENU), str); #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index 5f59843bbe..53d9d7a5ba 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -68,7 +68,7 @@ SCREEN_TABLE { #if HAS_BED_PROBE DECL_SCREEN(ZOffsetScreen), #endif -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND DECL_SCREEN(NozzleOffsetScreen), #endif #if ENABLED(BACKLASH_GCODE) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 06f64d38cb..c659f50fc1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -514,7 +514,7 @@ class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen 1 +#if HAS_MULTI_HOTEND class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { public: static void onEntry(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp index 81cde5a341..4025d16bbd 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp @@ -78,7 +78,7 @@ bool TemperatureScreen::onTouchHeld(uint8_t tag) { case 2: UI_DECREMENT(TargetTemp_celsius, E0); break; case 3: UI_INCREMENT(TargetTemp_celsius, E0); break; #endif - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND case 4: UI_DECREMENT(TargetTemp_celsius, E1); break; case 5: UI_INCREMENT(TargetTemp_celsius, E1); break; #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index b5f94539fe..55ae020616 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -192,7 +192,7 @@ namespace ExtUI { case CHAMBER: return; // Chamber has no idle timer #endif default: - #if HOTENDS + #if HAS_HOTEND thermalManager.reset_hotend_idle_timer(heater - H0); #endif break; @@ -258,7 +258,7 @@ namespace ExtUI { case CHAMBER: return false; // Chamber has no idle timer #endif default: - #if HOTENDS + #if HAS_HOTEND return thermalManager.hotend_idle[heater - H0].timed_out; #else return false; @@ -985,7 +985,7 @@ namespace ExtUI { else #endif { - #if HOTENDS + #if HAS_HOTEND static constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); const int16_t e = heater - H0; thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e); @@ -997,7 +997,7 @@ namespace ExtUI { #ifdef TOUCH_UI_LCD_TEMP_SCALING value *= TOUCH_UI_LCD_TEMP_SCALING; #endif - #if HOTENDS + #if HAS_HOTEND constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); const int16_t e = extruder - E0; enableHeater(extruder); diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 5d4b655167..5f3e6d965a 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -29,7 +29,7 @@ extern int8_t encoderLine, encoderTopLine, screen_items; -#if HOTENDS +#if HAS_HOTEND constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index ac755af7c4..f0bbfdfed1 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -233,9 +233,9 @@ void menu_cancelobject(); #define DEFINE_PIDTEMP_FUNCS(N) _DEFINE_PIDTEMP_BASE_FUNCS(N); #endif -#if HOTENDS +#if HAS_HOTEND DEFINE_PIDTEMP_FUNCS(0); - #if HOTENDS > 1 && ENABLED(PID_PARAMS_PER_HOTEND) + #if HAS_MULTI_HOTEND && ENABLED(PID_PARAMS_PER_HOTEND) REPEAT_S(1, HOTENDS, DEFINE_PIDTEMP_FUNCS) #endif #endif @@ -308,7 +308,7 @@ void menu_cancelobject(); #endif PID_EDIT_MENU_ITEMS(0); - #if HOTENDS > 1 && ENABLED(PID_PARAMS_PER_HOTEND) + #if HAS_MULTI_HOTEND && ENABLED(PID_PARAMS_PER_HOTEND) REPEAT_S(1, HOTENDS, PID_EDIT_MENU_ITEMS) #endif diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index b00a3d964a..5229093fd6 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -48,7 +48,7 @@ uint8_t MarlinUI::preheat_fan_speed[2]; // void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const uint8_t fan) { - #if HOTENDS + #if HAS_HOTEND if (temph > 0) thermalManager.setTargetHotend(_MIN(heater_maxtemp[endnum] - 15, temph), endnum); #endif #if HAS_HEATED_BED @@ -107,7 +107,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #else ACTION_ITEM(MSG_PREHEAT_1, []{ _preheat_end(0, 0); }); #endif - #elif HOTENDS > 1 + #elif HAS_MULTI_HOTEND #if HAS_HEATED_BED _PREHEAT_ITEMS(1,0); #endif @@ -118,7 +118,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #endif HOTEND_LOOP() thermalManager.setTargetHotend(ui.preheat_hotend_temp[0], e); }); - #endif // HOTENDS > 1 + #endif // HAS_MULTI_HOTEND #if HAS_HEATED_BED ACTION_ITEM(MSG_PREHEAT_1_BEDONLY, []{ _preheat_bed(0); }); #endif @@ -135,7 +135,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #else ACTION_ITEM(MSG_PREHEAT_2, []{ _preheat_end(1, 0); }); #endif - #elif HOTENDS > 1 + #elif HAS_MULTI_HOTEND #if HAS_HEATED_BED _PREHEAT_ITEMS(2,0); #endif @@ -146,7 +146,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #endif HOTEND_LOOP() thermalManager.setTargetHotend(ui.preheat_hotend_temp[1], e); }); - #endif // HOTENDS > 1 + #endif // HAS_MULTI_HOTEND #if HAS_HEATED_BED ACTION_ITEM(MSG_PREHEAT_2_BEDONLY, []{ _preheat_bed(1); }); #endif @@ -171,7 +171,7 @@ void menu_temperature() { // #if HOTENDS == 1 EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - 15, []{ thermalManager.start_watching_hotend(0); }); - #elif HOTENDS > 1 + #elif HAS_MULTI_HOTEND HOTEND_LOOP() EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - 15, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index ac18e89df4..a36f6afc90 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -127,7 +127,7 @@ void menu_tune() { // #if HOTENDS == 1 EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - 15, []{ thermalManager.start_watching_hotend(0); }); - #elif HOTENDS > 1 + #elif HAS_MULTI_HOTEND HOTEND_LOOP() EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - 15, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 0211c303eb..cdc4432a53 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -3194,7 +3194,7 @@ void MarlinSettings::reset() { HOTEND_LOOP() { CONFIG_ECHO_START(); SERIAL_ECHOPAIR_P( - #if HOTENDS > 1 && ENABLED(PID_PARAMS_PER_HOTEND) + #if HAS_MULTI_HOTEND && ENABLED(PID_PARAMS_PER_HOTEND) PSTR(" M301 E"), e, SP_P_STR #else diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 650cda51f3..0ca7535ec7 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -140,7 +140,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, bool Temperature::adaptive_fan_slowing = true; #endif -#if HOTENDS +#if HAS_HOTEND hotend_info_t Temperature::temp_hotend[HOTEND_TEMPS]; // = { 0 } #endif @@ -298,7 +298,7 @@ volatile bool Temperature::raw_temps_ready = false; #define TEMPDIR(N) ((HEATER_##N##_RAW_LO_TEMP) < (HEATER_##N##_RAW_HI_TEMP) ? 1 : -1) -#if HOTENDS +#if HAS_HOTEND // Init mintemp and maxtemp with extreme values to prevent false errors during startup constexpr temp_range_t sensor_heater_0 { HEATER_0_RAW_LO_TEMP, HEATER_0_RAW_HI_TEMP, 0, 16383 }, sensor_heater_1 { HEATER_1_RAW_LO_TEMP, HEATER_1_RAW_HI_TEMP, 0, 16383 }, @@ -655,7 +655,7 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { #endif default: return (0 - #if HOTENDS + #if HAS_HOTEND + temp_hotend[heater_id].soft_pwm_amount #endif ); @@ -672,7 +672,7 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { #define _EFAN(B,A) _EFANOVERLAP(A,B) ? B : static const uint8_t fanBit[] PROGMEM = { 0 - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #define _NEXT_FAN(N) , REPEAT2(N,_EFAN,N) N RREPEAT_S(1, HOTENDS, _NEXT_FAN) #endif @@ -821,7 +821,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { _temp_error(heater, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); } -#if HOTENDS +#if HAS_HOTEND #if ENABLED(PID_DEBUG) extern bool pid_debug_flag; #endif @@ -1036,7 +1036,7 @@ void Temperature::manage_heater() { millis_t ms = millis(); - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) @@ -1384,7 +1384,7 @@ void Temperature::manage_heater() { } #endif -#if HOTENDS +#if HAS_HOTEND // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. float Temperature::analog_to_celsius_hotend(const int raw, const uint8_t e) { @@ -1575,7 +1575,7 @@ void Temperature::updateTemperaturesFromRawValues() { #if ENABLED(HEATER_1_USES_MAX6675) temp_hotend[1].raw = READ_MAX6675(1); #endif - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif #if HAS_HEATED_BED @@ -1836,7 +1836,7 @@ void Temperature::init() { // Wait for temperature measurement to settle delay(250); - #if HOTENDS + #if HAS_HOTEND #define _TEMP_MIN_E(NR) do{ \ temp_range[NR].mintemp = HEATER_ ##NR## _MINTEMP; \ @@ -1855,7 +1855,7 @@ void Temperature::init() { #ifdef HEATER_0_MAXTEMP _TEMP_MAX_E(0); #endif - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #ifdef HEATER_1_MINTEMP _TEMP_MIN_E(1); #endif @@ -1910,7 +1910,7 @@ void Temperature::init() { #endif // HOTENDS > 4 #endif // HOTENDS > 3 #endif // HOTENDS > 2 - #endif // HOTENDS > 1 + #endif // HAS_MULTI_HOTEND #endif // HOTENDS @@ -2070,7 +2070,7 @@ void Temperature::disable_all_heaters() { planner.autotemp_enabled = false; #endif - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() setTargetHotend(0, e); #endif @@ -2113,7 +2113,7 @@ void Temperature::disable_all_heaters() { #if ENABLED(PRINTJOB_TIMER_AUTOSTART) bool Temperature::over_autostart_threshold() { - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() if (degTargetHotend(e) > (EXTRUDE_MINTEMP) / 2) return true; #endif #if HAS_HEATED_BED @@ -2358,7 +2358,7 @@ void Temperature::readings_ready() { filwidth.reading_ready(); #endif - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].reset(); #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) temp_hotend[1].reset(); @@ -2387,7 +2387,7 @@ void Temperature::readings_ready() { joystick.z.reset(); #endif - #if HOTENDS + #if HAS_HOTEND static constexpr int8_t temp_dir[] = { #if ENABLED(HEATER_0_USES_MAX6675) @@ -2395,7 +2395,7 @@ void Temperature::readings_ready() { #else TEMPDIR(0) #endif - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #define _TEMPDIR(N) , TEMPDIR(N) #if ENABLED(HEATER_1_USES_MAX6675) , 0 @@ -2405,7 +2405,7 @@ void Temperature::readings_ready() { #if HOTENDS > 2 REPEAT_S(2, HOTENDS, _TEMPDIR) #endif // HOTENDS > 2 - #endif // HOTENDS > 1 + #endif // HAS_MULTI_HOTEND }; LOOP_L_N(e, COUNT(temp_dir)) { @@ -2531,7 +2531,7 @@ void Temperature::tick() { static bool ADCKey_pressed = false; #endif - #if HOTENDS + #if HAS_HOTEND static SoftPWM soft_pwm_hotend[HOTENDS]; #endif @@ -2565,7 +2565,7 @@ void Temperature::tick() { if (pwm_count_tmp >= 127) { pwm_count_tmp -= 127; - #if HOTENDS + #if HAS_HOTEND #define _PWM_MOD_E(N) _PWM_MOD(N,soft_pwm_hotend[N],temp_hotend[N]); REPEAT(HOTENDS, _PWM_MOD_E); #endif @@ -2612,7 +2612,7 @@ void Temperature::tick() { } else { #define _PWM_LOW(N,S) do{ if (S.count <= pwm_count_tmp) WRITE_HEATER_##N(LOW); }while(0) - #if HOTENDS + #if HAS_HOTEND #define _PWM_LOW_E(N) _PWM_LOW(N, soft_pwm_hotend[N]); REPEAT(HOTENDS, _PWM_LOW_E); #endif @@ -2678,7 +2678,7 @@ void Temperature::tick() { if (slow_pwm_count == 0) { - #if HOTENDS + #if HAS_HOTEND #define _SLOW_PWM_E(N) _SLOW_PWM(N, soft_pwm_hotend[N], temp_hotend[N]); REPEAT(HOTENDS, _SLOW_PWM_E); #endif @@ -2689,7 +2689,7 @@ void Temperature::tick() { } // slow_pwm_count == 0 - #if HOTENDS + #if HAS_HOTEND #define _PWM_OFF_E(N) _PWM_OFF(N, soft_pwm_hotend[N]); REPEAT(HOTENDS, _PWM_OFF_E); #endif @@ -2772,7 +2772,7 @@ void Temperature::tick() { slow_pwm_count++; slow_pwm_count &= 0x7F; - #if HOTENDS + #if HAS_HOTEND HOTEND_LOOP() soft_pwm_hotend[e].dec(); #endif #if HAS_HEATED_BED @@ -2990,7 +2990,7 @@ void Temperature::tick() { } SERIAL_CHAR(' '); SERIAL_CHAR(k); - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND if (e >= 0) SERIAL_CHAR('0' + e); #endif SERIAL_CHAR(':'); @@ -3052,7 +3052,7 @@ void Temperature::tick() { , H_PROBE ); #endif // HAS_TEMP_PROBE - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND HOTEND_LOOP() print_heater_state(degHotend(e), degTargetHotend(e) #if ENABLED(SHOW_TEMP_ADC_VALUES) , rawHotendTemp(e) @@ -3067,7 +3067,7 @@ void Temperature::tick() { #if HAS_HEATED_CHAMBER SERIAL_ECHOPAIR(" C@:", getHeaterPower(H_CHAMBER)); #endif - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND HOTEND_LOOP() { SERIAL_ECHOPAIR(" @", e); SERIAL_CHAR(':'); @@ -3096,7 +3096,7 @@ void Temperature::tick() { void Temperature::set_heating_message(const uint8_t e) { const bool heating = isHeatingHotend(e); ui.status_printf_P(0, - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND PSTR("E%c " S_FMT), '1' + e #else PSTR("E " S_FMT) diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index cba1642afd..981615c1b4 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -317,12 +317,12 @@ class Temperature { public: - #if HOTENDS #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) #define HOTEND_TEMPS (HOTENDS + 1) #else #define HOTEND_TEMPS HOTENDS #endif + #if HAS_HOTEND static hotend_info_t temp_hotend[HOTEND_TEMPS]; #endif #if HAS_HEATED_BED @@ -496,7 +496,7 @@ class Temperature { } #endif - #if HOTENDS + #if HAS_HOTEND static float analog_to_celsius_hotend(const int raw, const uint8_t e); #endif @@ -624,7 +624,7 @@ class Temperature { static inline void start_watching_hotend(const uint8_t=0) {} #endif - #if HOTENDS + #if HAS_HOTEND static void setTargetHotend(const int16_t celsius, const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 0bfbaabdcd..27d9bc11cc 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -142,7 +142,7 @@ // Augmentation for auto-assigning RAMPS plugs // #if NONE(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D) - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_BED #define IS_RAMPS_EEB #else diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index b8b04a348c..52dd9b2eb5 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -184,7 +184,7 @@ // Augmentation for auto-assigning RAMPS plugs // #if NONE(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D) - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_BED #define IS_RAMPS_EEB #else diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 3282216819..f3d338aa2a 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -159,7 +159,7 @@ #define HBP_PIN 45 // L4 #define EXTRA_FET_PIN 44 // L5 -#if HOTENDS > 1 +#if HAS_MULTI_HOTEND #if TEMP_SENSOR_BED #define IS_EEB #else diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 75d647fed5..8993d0ff57 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -124,7 +124,7 @@ // Augmentation for auto-assigning RAMPS plugs // #if NONE(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D) - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_BED #define IS_RAMPS_EEB #else diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 5176c699ee..4e62c67aaf 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -130,7 +130,7 @@ // Augmentation for auto-assigning RAMPS plugs // #if NONE(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D) - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_BED #define IS_RAMPS_EEB #else diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index ffe7f7bb1e..be3f33ebfd 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -180,7 +180,7 @@ // Augmentation for auto-assigning RAMPS plugs // #if NONE(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D) - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_BED #define IS_RAMPS_EEB #else diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index adbacfbf4d..cfb9acb054 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -59,7 +59,7 @@ #define RAMPS_D10_PIN TG_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h -#if HOTENDS > 1 // EEF and EEB +#if HAS_MULTI_HOTEND // EEF and EEB #define RAMPS_D9_PIN TG_HEATER_1_PIN #if !TEMP_SENSOR_BED // EEF @@ -79,7 +79,7 @@ #define RAMPS_D8_PIN TG_FAN0_PIN #endif -#if HOTENDS > 1 || TEMP_SENSOR_BED // EEF, EEB, EFB +#if HAS_MULTI_HOTEND || TEMP_SENSOR_BED // EEF, EEB, EFB #define FAN1_PIN TG_FAN1_PIN #endif #define FAN2_PIN TG_FAN2_PIN diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 12cadcbd9c..9ca5aa1ee2 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -423,10 +423,10 @@ #define _H6_PINS #define _H7_PINS -#if HOTENDS +#if HAS_HOTEND #undef _H0_PINS #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_0_PIN), - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND #undef _H1_PINS #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_1_PIN), #if HOTENDS > 2 @@ -453,7 +453,7 @@ #endif // HOTENDS > 4 #endif // HOTENDS > 3 #endif // HOTENDS > 2 - #endif // HOTENDS > 1 + #endif // HAS_MULTI_HOTEND #endif // HOTENDS // From a0d0ce464e4bc6b8115903e144979c6a1c0d1a8a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ond=C5=99ej=20Nov=C3=BD?= Date: Mon, 20 Apr 2020 13:54:24 +0200 Subject: [PATCH 0208/1454] Sanity-check nozzle park point (#17621) --- Marlin/src/inc/SanityCheck.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index fd81f8e4f6..b30097705f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -806,6 +806,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(NOZZLE_PARK_FEATURE) constexpr float npp[] = NOZZLE_PARK_POINT; static_assert(COUNT(npp) == XYZ, "NOZZLE_PARK_POINT requires X, Y, and Z values."); + constexpr xyz_pos_t npp_xyz = NOZZLE_PARK_POINT; + static_assert(WITHIN(npp_xyz.x, X_MIN_POS, X_MAX_POS), "NOZZLE_PARK_POINT.X is out of bounds (X_MIN_POS, X_MAX_POS)."); + static_assert(WITHIN(npp_xyz.y, Y_MIN_POS, Y_MAX_POS), "NOZZLE_PARK_POINT.Y is out of bounds (Y_MIN_POS, Y_MAX_POS)."); + static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); #endif /** From 1af6a6d4f96b7378f4437b2d1610dcbb96d21a7f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ond=C5=99ej=20Nov=C3=BD?= Date: Mon, 20 Apr 2020 13:55:55 +0200 Subject: [PATCH 0209/1454] Update Language fonts (#17620) --- .../lcd/dogm/fontdata/fontdata_ISO10646_1.h | 8 +- Marlin/src/lcd/dogm/fontdata/langdata_bg.h | 16 +- Marlin/src/lcd/dogm/fontdata/langdata_cz.h | 32 +- Marlin/src/lcd/dogm/fontdata/langdata_el.h | 22 +- Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h | 20 +- Marlin/src/lcd/dogm/fontdata/langdata_hr.h | 10 +- Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h | 65 +- Marlin/src/lcd/dogm/fontdata/langdata_pl.h | 19 +- Marlin/src/lcd/dogm/fontdata/langdata_ru.h | 12 +- Marlin/src/lcd/dogm/fontdata/langdata_sk.h | 37 +- Marlin/src/lcd/dogm/fontdata/langdata_test.h | 164 ++-- Marlin/src/lcd/dogm/fontdata/langdata_tr.h | 13 +- Marlin/src/lcd/dogm/fontdata/langdata_uk.h | 24 +- Marlin/src/lcd/dogm/fontdata/langdata_vi.h | 95 +- Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h | 531 +++++------ Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h | 831 +++++++++++------- 16 files changed, 1032 insertions(+), 867 deletions(-) diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index e3087a55df..b6930cb14c 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -26,14 +26,14 @@ Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 Capital A Height: 7, '1' Height: 7 Calculated Max Values w= 5 h=10 x= 5 y= 5 dx= 6 dy= 0 ascent= 8 len=10 - Font Bounding box w=12 h=13 x= 0 y=-2 + Font Bounding box w=12 h=15 x= 0 y=-2 Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 Pure Font ascent = 7 descent=-2 X Font ascent = 8 descent=-2 Max Font ascent = 8 descent=-2 */ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1325] U8G_FONT_SECTION("ISO10646_1_5x7") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x07,0x02,0x26,0x03,0xbc,0x01,0x7f,0xfe,0x08,0xfe,0x08, + 0x00,0x0c,0x0f,0x00,0xfe,0x07,0x02,0x26,0x03,0xbc,0x01,0x7f,0xfe,0x08,0xfe,0x08, 0xfe,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xf0,0xc8,0x88,0x88,0x98,0x78,0x10,0x05, 0x08,0x08,0x06,0x00,0x00,0xc0,0xf8,0x88,0x88,0x88,0x88,0x88,0xf8,0x05,0x05,0x05, 0x06,0x00,0x01,0x20,0x30,0xf8,0x30,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x70, @@ -124,14 +124,14 @@ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1325] U8G_FONT_SECTION("ISO10646_1_5x7") Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 Capital A Height: 7, '1' Height: 7 Calculated Max Values w= 6 h=10 x= 5 y= 7 dx= 6 dy= 0 ascent=10 len=10 - Font Bounding box w=12 h=13 x= 0 y=-2 + Font Bounding box w=12 h=15 x= 0 y=-2 Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 Pure Font ascent = 7 descent=-2 X Font ascent = 8 descent=-2 Max Font ascent =10 descent=-2 */ const u8g_fntpgm_uint8_t ISO10646_1_5x7[2648] U8G_FONT_SECTION("ISO10646_1_5x7") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x07,0x02,0x26,0x03,0xbc,0x01,0xff,0xfe,0x0a,0xfe,0x08, + 0x00,0x0c,0x0f,0x00,0xfe,0x07,0x02,0x26,0x03,0xbc,0x01,0xff,0xfe,0x0a,0xfe,0x08, 0xfe,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xf0,0xc8,0x88,0x88,0x98,0x78,0x10,0x05, 0x08,0x08,0x06,0x00,0x00,0xc0,0xf8,0x88,0x88,0x88,0x88,0x88,0xf8,0x05,0x05,0x05, 0x06,0x00,0x01,0x20,0x30,0xf8,0x30,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x70, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h index 81444d9969..5fd7931f23 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h @@ -6,7 +6,7 @@ #include const u8g_fntpgm_uint8_t fontpage_8_144_149[96] U8G_FONT_SECTION("fontpage_8_144_149") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x95,0x00,0x07,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x95,0x00,0x07,0xff,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x80,0x80,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, 0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80, @@ -14,11 +14,11 @@ const u8g_fntpgm_uint8_t fontpage_8_144_149[96] U8G_FONT_SECTION("fontpage_8_144 0x50,0xf8,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8 }; const u8g_fntpgm_uint8_t fontpage_8_151_152[43] U8G_FONT_SECTION("fontpage_8_151_152") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x98,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x98,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x08,0x70,0x08,0x88,0x70,0x05,0x07, 0x07,0x06,0x00,0x00,0x88,0x88,0x98,0xa8,0xc8,0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_8_154_164[160] U8G_FONT_SECTION("fontpage_8_154_164") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0xa4,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0xa4,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0,0xc0,0xa0,0x90,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x48,0x48,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88, @@ -30,11 +30,11 @@ const u8g_fntpgm_uint8_t fontpage_8_154_164[160] U8G_FONT_SECTION("fontpage_8_15 0x78,0x08,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x70,0xa8,0xa8,0xa8,0x70,0x20 }; const u8g_fntpgm_uint8_t fontpage_8_166_166[32] U8G_FONT_SECTION("fontpage_8_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x07,0xfe,0x00, 0x00,0x05,0x09,0x09,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0x90,0x90,0xf8,0x08,0x08 }; const u8g_fntpgm_uint8_t fontpage_8_175_195[260] U8G_FONT_SECTION("fontpage_8_175_195") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xc3,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xc3,0x00,0x08,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x78,0x88,0x88,0x78,0x28,0x48,0x88,0x05,0x05, 0x05,0x06,0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x70, 0x80,0xf0,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf0,0x88,0xf0,0x88, @@ -52,15 +52,15 @@ const u8g_fntpgm_uint8_t fontpage_8_175_195[260] U8G_FONT_SECTION("fontpage_8_17 0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0xfe,0x88,0x88,0x88, 0x88,0x78,0x08,0x70}; const u8g_fntpgm_uint8_t fontpage_8_197_200[63] U8G_FONT_SECTION("fontpage_8_197_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc8,0x00,0x05,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc8,0x00,0x05,0xfe,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07,0x07,0x06, 0x00,0xfe,0x90,0x90,0x90,0x90,0xf8,0x08,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0x88, 0x88,0x78,0x08,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8,0xf8}; const u8g_fntpgm_uint8_t fontpage_8_202_202[28] U8G_FONT_SECTION("fontpage_8_202_202") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0xc0,0x40,0x70,0x48,0x70}; const u8g_fntpgm_uint8_t fontpage_8_206_207[39] U8G_FONT_SECTION("fontpage_8_206_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xcf,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xcf,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x90,0xa8,0xe8,0xa8,0x90,0x04,0x05,0x05,0x06, 0x01,0x00,0x70,0x90,0x70,0x50,0x90}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h index e132dc8160..998536fea1 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h @@ -6,35 +6,37 @@ #include const u8g_fntpgm_uint8_t fontpage_2_140_141[47] U8G_FONT_SECTION("fontpage_2_140_141") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8d,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8d,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x80,0x80,0x88, 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_2_143_143[33] U8G_FONT_SECTION("fontpage_2_143_143") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0x00,0x00, 0x00,0x06,0x0a,0x0a,0x06,0x00,0x00,0x14,0x08,0x00,0x08,0x08,0x78,0x88,0x88,0x88, 0x78}; -const u8g_fntpgm_uint8_t fontpage_2_155_155[31] U8G_FONT_SECTION("fontpage_2_155_155") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x08,0x00,0x00, - 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0xf0,0x80,0x70}; +const u8g_fntpgm_uint8_t fontpage_2_154_155[47] U8G_FONT_SECTION("fontpage_2_154_155") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9b,0x00,0x0a,0x00,0x00, + 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80, + 0xf8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0xf0,0x80,0x70}; const u8g_fntpgm_uint8_t fontpage_2_200_200[31] U8G_FONT_SECTION("fontpage_2_200_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xb0,0xc8,0x88,0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_2_216_217[47] U8G_FONT_SECTION("fontpage_2_216_217") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd9,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd9,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0xf0,0x88,0x88,0xf0,0xa0,0x90, 0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xb0,0xc8,0x80,0x80,0x80}; -const u8g_fntpgm_uint8_t fontpage_2_225_225[31] U8G_FONT_SECTION("fontpage_2_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x08,0x00,0x00, - 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x78,0x80,0x70,0x08,0xf0}; +const u8g_fntpgm_uint8_t fontpage_2_224_225[47] U8G_FONT_SECTION("fontpage_2_224_225") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe1,0x00,0x0a,0x00,0x00, + 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x70,0x08,0x88, + 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x78,0x80,0x70,0x08,0xf0}; const u8g_fntpgm_uint8_t fontpage_2_229_229[33] U8G_FONT_SECTION("fontpage_2_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x20,0x20,0xf8,0x20,0x20,0x20, 0x18}; const u8g_fntpgm_uint8_t fontpage_2_239_239[31] U8G_FONT_SECTION("fontpage_2_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x50,0x20,0x88,0x88,0x88,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253_254") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfe,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfe,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x08,0x10,0x20,0x40,0x80, 0xf8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x10,0x20,0x40,0xf8}; @@ -42,10 +44,10 @@ const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253 static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' FONTDATA_ITEM(2, 143, 143, fontpage_2_143_143), // 'ď' -- 'ď' - FONTDATA_ITEM(2, 155, 155, fontpage_2_155_155), // 'ě' -- 'ě' + FONTDATA_ITEM(2, 154, 155, fontpage_2_154_155), // 'Ě' -- 'ě' FONTDATA_ITEM(2, 200, 200, fontpage_2_200_200), // 'ň' -- 'ň' FONTDATA_ITEM(2, 216, 217, fontpage_2_216_217), // 'Ř' -- 'ř' - FONTDATA_ITEM(2, 225, 225, fontpage_2_225_225), // 'š' -- 'š' + FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' FONTDATA_ITEM(2, 239, 239, fontpage_2_239_239), // 'ů' -- 'ů' FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el.h b/Marlin/src/lcd/dogm/fontdata/langdata_el.h index 858ec0f84f..284706a817 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el.h @@ -6,11 +6,11 @@ #include const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x80,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80, 0xf8}; const u8g_fntpgm_uint8_t fontpage_7_145_157[186] U8G_FONT_SECTION("fontpage_7_145_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x9d,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x9d,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, 0x00,0xf8,0x80,0x80,0x80,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20, @@ -23,35 +23,35 @@ const u8g_fntpgm_uint8_t fontpage_7_145_157[186] U8G_FONT_SECTION("fontpage_7_14 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07,0x07, 0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_7_159_161[56] U8G_FONT_SECTION("fontpage_7_159_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0xa1,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0xa1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07, 0x07,0x06,0x00,0x00,0xf8,0x88,0x88,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0xf0,0x88,0x88,0xf0,0x80,0x80,0x80}; const u8g_fntpgm_uint8_t fontpage_7_163_167[82] U8G_FONT_SECTION("fontpage_7_163_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa7,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa7,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x40,0x20,0x10,0x20,0x40,0xf8,0x05,0x07, 0x07,0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00, 0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x70, 0xa8,0xa8,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50, 0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_7_169_169[30] U8G_FONT_SECTION("fontpage_7_169_169") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0x88,0x50,0xd8}; const u8g_fntpgm_uint8_t fontpage_7_172_175[75] U8G_FONT_SECTION("fontpage_7_172_175") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xaf,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xaf,0x00,0x08,0xfe,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x68,0x90,0x90,0x90,0x68,0x05, 0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x60,0x88,0x70,0x05,0x0a,0x0a, 0x06,0x00,0xfe,0x10,0x20,0x00,0xb0,0xc8,0x88,0x88,0x88,0x08,0x08,0x03,0x08,0x08, 0x06,0x01,0x00,0x40,0x80,0x00,0x80,0x80,0x80,0xa0,0x40}; const u8g_fntpgm_uint8_t fontpage_7_177_181[80] U8G_FONT_SECTION("fontpage_7_177_181") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb5,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb5,0x00,0x07,0xfe,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x68,0x90,0x90,0x90,0x68,0x05,0x09,0x09,0x06, 0x00,0xfe,0x60,0x90,0x90,0xb0,0x88,0x88,0xf0,0x80,0x80,0x05,0x07,0x07,0x06,0x00, 0xfe,0x88,0x88,0x50,0x50,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x80, 0x70,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88,0x60,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_7_183_199[226] U8G_FONT_SECTION("fontpage_7_183_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xc7,0x00,0x09,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xc7,0x00,0x09,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0xfe,0xb0,0xc8,0x88,0x88,0x88,0x08,0x08,0x04,0x07, 0x07,0x06,0x01,0x00,0x60,0x90,0x90,0xf0,0x90,0x90,0x60,0x03,0x05,0x05,0x06,0x02, 0x00,0x80,0x80,0x80,0xa0,0x40,0x04,0x05,0x05,0x06,0x01,0x00,0x90,0xa0,0xc0,0xa0, @@ -67,15 +67,15 @@ const u8g_fntpgm_uint8_t fontpage_7_183_199[226] U8G_FONT_SECTION("fontpage_7_18 0xa8,0xa8,0x70,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0xfe,0x88,0x88,0x50,0x20,0x50, 0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_7_201_201[28] U8G_FONT_SECTION("fontpage_7_201_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x50,0x88,0xa8,0xa8,0x50}; const u8g_fntpgm_uint8_t fontpage_7_204_206[59] U8G_FONT_SECTION("fontpage_7_204_206") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xce,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xce,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x88,0x88,0x70,0x05, 0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x90,0x88,0x88,0x88,0x70,0x05,0x08,0x08, 0x06,0x00,0x00,0x10,0x20,0x00,0x50,0x88,0xa8,0xa8,0x50}; const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x01,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xa8}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h index 76a5c66cd9..6d864c9c9a 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h @@ -6,11 +6,11 @@ #include const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x80,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80, 0xf8}; const u8g_fntpgm_uint8_t fontpage_7_145_157[186] U8G_FONT_SECTION("fontpage_7_145_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x9d,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x9d,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, 0x00,0xf8,0x80,0x80,0x80,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20, @@ -23,32 +23,32 @@ const u8g_fntpgm_uint8_t fontpage_7_145_157[186] U8G_FONT_SECTION("fontpage_7_14 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07,0x07, 0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_7_159_161[56] U8G_FONT_SECTION("fontpage_7_159_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0xa1,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0xa1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07, 0x07,0x06,0x00,0x00,0xf8,0x88,0x88,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0xf0,0x88,0x88,0xf0,0x80,0x80,0x80}; const u8g_fntpgm_uint8_t fontpage_7_163_167[82] U8G_FONT_SECTION("fontpage_7_163_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa7,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa7,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x40,0x20,0x10,0x20,0x40,0xf8,0x05,0x07, 0x07,0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00, 0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x70, 0xa8,0xa8,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50, 0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_7_172_175[75] U8G_FONT_SECTION("fontpage_7_172_175") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xaf,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xaf,0x00,0x08,0xfe,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x68,0x90,0x90,0x90,0x68,0x05, 0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x60,0x88,0x70,0x05,0x0a,0x0a, 0x06,0x00,0xfe,0x10,0x20,0x00,0xb0,0xc8,0x88,0x88,0x88,0x08,0x08,0x03,0x08,0x08, 0x06,0x01,0x00,0x40,0x80,0x00,0x80,0x80,0x80,0xa0,0x40}; const u8g_fntpgm_uint8_t fontpage_7_177_181[80] U8G_FONT_SECTION("fontpage_7_177_181") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb5,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb5,0x00,0x07,0xfe,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x68,0x90,0x90,0x90,0x68,0x05,0x09,0x09,0x06, 0x00,0xfe,0x60,0x90,0x90,0xb0,0x88,0x88,0xf0,0x80,0x80,0x05,0x07,0x07,0x06,0x00, 0xfe,0x88,0x88,0x50,0x50,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x80, 0x70,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88,0x60,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_7_183_199[226] U8G_FONT_SECTION("fontpage_7_183_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xc7,0x00,0x09,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xc7,0x00,0x09,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0xfe,0xb0,0xc8,0x88,0x88,0x88,0x08,0x08,0x04,0x07, 0x07,0x06,0x01,0x00,0x60,0x90,0x90,0xf0,0x90,0x90,0x60,0x03,0x05,0x05,0x06,0x02, 0x00,0x80,0x80,0x80,0xa0,0x40,0x04,0x05,0x05,0x06,0x01,0x00,0x90,0xa0,0xc0,0xa0, @@ -64,15 +64,15 @@ const u8g_fntpgm_uint8_t fontpage_7_183_199[226] U8G_FONT_SECTION("fontpage_7_18 0xa8,0xa8,0x70,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0xfe,0x88,0x88,0x50,0x20,0x50, 0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_7_201_201[28] U8G_FONT_SECTION("fontpage_7_201_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x50,0x88,0xa8,0xa8,0x50}; const u8g_fntpgm_uint8_t fontpage_7_204_206[59] U8G_FONT_SECTION("fontpage_7_204_206") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xce,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xce,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x88,0x88,0x70,0x05, 0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x90,0x88,0x88,0x88,0x70,0x05,0x08,0x08, 0x06,0x00,0x00,0x10,0x20,0x00,0x50,0x88,0xa8,0xa8,0x50}; const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x01,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xa8}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h index 63fea945b2..6337c9226a 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h @@ -6,20 +6,20 @@ #include const u8g_fntpgm_uint8_t fontpage_2_135_135[31] U8G_FONT_SECTION("fontpage_2_135_135") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x80,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_2_140_141[47] U8G_FONT_SECTION("fontpage_2_140_141") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8d,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8d,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x80,0x80,0x88, 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_2_145_145[31] U8G_FONT_SECTION("fontpage_2_145_145") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x08,0x00,0x00, 0x00,0x06,0x08,0x08,0x06,0x00,0x00,0x08,0x1c,0x08,0x78,0x88,0x88,0x88,0x78}; const u8g_fntpgm_uint8_t fontpage_2_225_225[31] U8G_FONT_SECTION("fontpage_2_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x78,0x80,0x70,0x08,0xf0}; const u8g_fntpgm_uint8_t fontpage_2_254_254[31] U8G_FONT_SECTION("fontpage_2_254_254") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfe,0xfe,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfe,0xfe,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x10,0x20,0x40,0xf8}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h index 9f20e7b401..e920b61631 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h @@ -77,14 +77,14 @@ const u8g_fntpgm_uint8_t fontpage_360_152_152[45] U8G_FONT_SECTION("fontpage_360 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x98,0x98,0x00,0x09,0xfe,0x00, 0x00,0x09,0x0b,0x16,0x0a,0x00,0xfe,0x7c,0x80,0x40,0x80,0x40,0x80,0x40,0x80,0x7e, 0x80,0x10,0x80,0x10,0x80,0xff,0x80,0x00,0x80,0x00,0x80,0x00,0x80}; +const u8g_fntpgm_uint8_t fontpage_360_156_156[45] U8G_FONT_SECTION("fontpage_360_156_156") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x9c,0x9c,0x00,0x09,0xfe,0x00, + 0x00,0x09,0x0b,0x16,0x0a,0x00,0xfe,0x7c,0x80,0x40,0x80,0x40,0x80,0x7c,0x80,0x10, + 0x80,0x10,0x80,0xff,0x80,0x00,0x80,0x20,0x00,0x20,0x00,0x3f,0x80}; const u8g_fntpgm_uint8_t fontpage_360_168_168[34] U8G_FONT_SECTION("fontpage_360_168_168") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x81,0x81,0xf9,0x21,0xff,0x00,0x7f,0x41, 0x41,0x7f}; -const u8g_fntpgm_uint8_t fontpage_360_208_208[43] U8G_FONT_SECTION("fontpage_360_208_208") = { - 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x09,0xff,0x00, - 0x00,0x0a,0x0a,0x14,0x0a,0x00,0xff,0x3f,0x80,0x20,0x00,0x20,0x00,0x20,0x00,0x3f, - 0x80,0x00,0x00,0xff,0xc0,0x04,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_361_164_164[45] U8G_FONT_SECTION("fontpage_361_164_164") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x09,0xfe,0x00, 0x00,0x09,0x0b,0x16,0x0a,0x00,0xfe,0x7c,0x80,0x40,0x80,0x40,0x80,0x40,0x80,0x7c, @@ -101,6 +101,10 @@ const u8g_fntpgm_uint8_t fontpage_366_252_252[45] U8G_FONT_SECTION("fontpage_366 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xfc,0xfc,0x00,0x09,0xfe,0x00, 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0xf9,0x00,0x09,0x00,0x09,0x00,0xf9,0x00,0x81, 0x80,0x81,0x00,0x81,0x00,0xfd,0x00,0x01,0x00,0x01,0x00,0x01,0x00}; +const u8g_fntpgm_uint8_t fontpage_367_236_236[34] U8G_FONT_SECTION("fontpage_367_236_236") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xec,0xec,0x00,0x09,0xfe,0x00, + 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf1,0x09,0x09,0xf1,0x87,0x81,0x81,0xf9,0x01, + 0x01,0x01}; const u8g_fntpgm_uint8_t fontpage_368_136_136[34] U8G_FONT_SECTION("fontpage_368_136_136") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf5,0x15,0x15,0xf5,0x8d,0x85,0x85,0xfd,0x05, @@ -125,6 +129,10 @@ const u8g_fntpgm_uint8_t fontpage_371_172_172[34] U8G_FONT_SECTION("fontpage_371 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x09,0x09,0xf9,0x81,0x81,0x81,0xfd,0x01, 0x01,0x01}; +const u8g_fntpgm_uint8_t fontpage_371_176_176[34] U8G_FONT_SECTION("fontpage_371_176_176") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x09,0xfe,0x00, + 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x09,0x09,0xf9,0x81,0x81,0xfd,0x01,0x20, + 0x20,0x3f}; const u8g_fntpgm_uint8_t fontpage_371_189_189[34] U8G_FONT_SECTION("fontpage_371_189_189") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x09,0xf9,0x81,0x81,0xfd,0x00,0x41,0x3f, @@ -133,10 +141,6 @@ const u8g_fntpgm_uint8_t fontpage_371_193_193[34] U8G_FONT_SECTION("fontpage_371 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xc1,0xc1,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x09,0xf9,0x81,0x81,0xfd,0x01,0x3e,0x21, 0x21,0x3e}; -const u8g_fntpgm_uint8_t fontpage_371_204_204[45] U8G_FONT_SECTION("fontpage_371_204_204") = { - 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x09,0xfe,0x00, - 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0xf9,0x00,0x89,0x00,0x89,0x00,0x89,0x80,0x89, - 0x00,0xf9,0x00,0x01,0x00,0x41,0x00,0x40,0x00,0x40,0x00,0x7f,0x00}; const u8g_fntpgm_uint8_t fontpage_372_200_200[34] U8G_FONT_SECTION("fontpage_372_200_200") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x89,0x89,0x8f,0x89,0xf9,0x00,0x3f,0x41, @@ -153,6 +157,14 @@ const u8g_fntpgm_uint8_t fontpage_373_168_168[41] U8G_FONT_SECTION("fontpage_373 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x09,0x00,0x00, 0x00,0x0a,0x09,0x12,0x0a,0x00,0x00,0x3f,0x80,0x20,0x80,0x20,0x80,0x20,0x80,0x3f, 0x80,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xc0}; +const u8g_fntpgm_uint8_t fontpage_373_187_187[45] U8G_FONT_SECTION("fontpage_373_187_187") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x09,0xfe,0x00, + 0x00,0x0a,0x0b,0x16,0x0a,0x00,0xfe,0x3f,0x00,0x20,0x80,0x20,0x80,0x3f,0x00,0x04, + 0x00,0xff,0xc0,0x00,0x00,0x04,0x00,0x0c,0x00,0x1a,0x00,0x61,0x80}; +const u8g_fntpgm_uint8_t fontpage_375_248_248[34] U8G_FONT_SECTION("fontpage_375_248_248") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x09,0xfe,0x00, + 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x89,0x89,0x89,0x89,0x89,0x89,0xf9,0x01, + 0x01,0x01}; const u8g_fntpgm_uint8_t fontpage_376_128_128[34] U8G_FONT_SECTION("fontpage_376_128_128") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x89,0x89,0x89,0xf9,0x00,0x3f,0x01,0x3f, @@ -173,14 +185,18 @@ const u8g_fntpgm_uint8_t fontpage_377_168_168[34] U8G_FONT_SECTION("fontpage_377 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0x95,0x95,0xfd,0x95,0xf5,0x00,0x3f,0x01,0x3f, 0x40,0x3f}; -const u8g_fntpgm_uint8_t fontpage_380_140_140[41] U8G_FONT_SECTION("fontpage_380_140_140") = { - 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x09,0x00,0x00, - 0x00,0x0a,0x09,0x12,0x0a,0x00,0x00,0x20,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0x20, - 0x80,0x3f,0x80,0x00,0x00,0x00,0x00,0xff,0xc0}; +const u8g_fntpgm_uint8_t fontpage_377_248_248[45] U8G_FONT_SECTION("fontpage_377_248_248") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x09,0xfe,0x00, + 0x00,0x0a,0x0b,0x16,0x0a,0x00,0xfe,0x20,0x80,0x20,0x80,0x3f,0x00,0x20,0x80,0x3f, + 0x00,0x04,0x00,0xff,0xc0,0x00,0x00,0x20,0x00,0x20,0x00,0x3f,0x80}; const u8g_fntpgm_uint8_t fontpage_380_196_196[34] U8G_FONT_SECTION("fontpage_380_196_196") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xc4,0xc4,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0x89,0x89,0x89,0xf9,0x89,0x89,0x89,0xf9,0x01, 0x01,0x01}; +const u8g_fntpgm_uint8_t fontpage_385_172_172[45] U8G_FONT_SECTION("fontpage_385_172_172") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x09,0xfe,0x00, + 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0x21,0x00,0x21,0x00,0x21,0x00,0x21,0x00,0x61, + 0x80,0x51,0x00,0x99,0x00,0x89,0x00,0x01,0x00,0x01,0x00,0x01,0x00}; const u8g_fntpgm_uint8_t fontpage_385_189_189[45] U8G_FONT_SECTION("fontpage_385_189_189") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x09,0xfe,0x00, 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0x21,0x00,0x21,0x00,0x21,0x00,0x51,0x80,0xd9, @@ -193,10 +209,6 @@ const u8g_fntpgm_uint8_t fontpage_386_164_164[34] U8G_FONT_SECTION("fontpage_386 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0x21,0x21,0x27,0x51,0x89,0x00,0x3f,0x01,0x3f, 0x40,0x3f}; -const u8g_fntpgm_uint8_t fontpage_386_216_216[34] U8G_FONT_SECTION("fontpage_386_216_216") = { - 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x09,0xfe,0x00, - 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0x21,0x27,0x21,0x67,0xd1,0x89,0x01,0x21,0x20, - 0x20,0x3f}; const u8g_fntpgm_uint8_t fontpage_387_140_141[69] U8G_FONT_SECTION("fontpage_387_140_141") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x8c,0x8d,0x00,0x09,0xfe,0x00, 0x00,0x0a,0x09,0x12,0x0a,0x00,0x00,0x04,0x00,0x0c,0x00,0x0c,0x00,0x12,0x00,0x31, @@ -287,6 +299,10 @@ const u8g_fntpgm_uint8_t fontpage_399_144_145[73] U8G_FONT_SECTION("fontpage_399 0x80,0x71,0x00,0xc9,0x00,0x85,0x00,0x01,0x00,0x01,0x00,0x01,0x00,0x09,0x0b,0x16, 0x0a,0x01,0xfe,0xf9,0x00,0x09,0x00,0x11,0x00,0x31,0x80,0x49,0x00,0x85,0x00,0x00, 0x00,0x7e,0x00,0x01,0x00,0x01,0x00,0x01,0x00}; +const u8g_fntpgm_uint8_t fontpage_399_152_152[45] U8G_FONT_SECTION("fontpage_399_152_152") = { + 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x98,0x98,0x00,0x09,0xfe,0x00, + 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0xf9,0x00,0x11,0x00,0x11,0x80,0x79,0x00,0x85, + 0x00,0x00,0x00,0x7e,0x00,0x01,0x00,0x7e,0x00,0x40,0x00,0x7f,0x00}; const u8g_fntpgm_uint8_t fontpage_399_165_165[45] U8G_FONT_SECTION("fontpage_399_165_165") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xa5,0xa5,0x00,0x09,0xfe,0x00, 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0xf9,0x00,0x09,0x00,0x11,0x00,0x31,0x80,0x79, @@ -367,10 +383,6 @@ const u8g_fntpgm_uint8_t fontpage_412_244_244[45] U8G_FONT_SECTION("fontpage_412 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x09,0xfe,0x00, 0x00,0x09,0x0b,0x16,0x0a,0x01,0xfe,0xf9,0x00,0x09,0x00,0x09,0x00,0xf1,0x00,0x11, 0x80,0x21,0x00,0x41,0x00,0x81,0x00,0x01,0x00,0x01,0x00,0x01,0x00}; -const u8g_fntpgm_uint8_t fontpage_413_152_152[34] U8G_FONT_SECTION("fontpage_413_152_152") = { - 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x98,0x98,0x00,0x09,0xfe,0x00, - 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf5,0x15,0xf7,0x25,0xc5,0x00,0x3f,0x01,0x3f, - 0x40,0x3f}; const u8g_fntpgm_uint8_t fontpage_414_156_156[34] U8G_FONT_SECTION("fontpage_414_156_156") = { 0x00,0x0b,0x0d,0x00,0xfd,0x00,0x00,0x00,0x00,0x00,0x9c,0x9c,0x00,0x09,0xfe,0x00, 0x00,0x08,0x0b,0x0b,0x0a,0x01,0xfe,0xf9,0x09,0x0f,0xf1,0x11,0x2f,0x41,0x81,0x01, @@ -444,36 +456,39 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(359, 204, 204, fontpage_359_204_204), // '돌' -- '돌' FONTDATA_ITEM(359, 217, 217, fontpage_359_217_217), // '동' -- '동' FONTDATA_ITEM(360, 152, 152, fontpage_360_152_152), // '되' -- '되' + FONTDATA_ITEM(360, 156, 156, fontpage_360_156_156), // '된' -- '된' FONTDATA_ITEM(360, 168, 168, fontpage_360_168_168), // '됨' -- '됨' - FONTDATA_ITEM(360, 208, 208, fontpage_360_208_208), // '두' -- '두' FONTDATA_ITEM(361, 164, 164, fontpage_361_164_164), // '뒤' -- '뒤' FONTDATA_ITEM(361, 220, 220, fontpage_361_220_220), // '드' -- '드' FONTDATA_ITEM(362, 148, 148, fontpage_362_148_148), // '디' -- '디' FONTDATA_ITEM(366, 252, 252, fontpage_366_252_252), // '라' -- '라' + FONTDATA_ITEM(367, 236, 236, fontpage_367_236_236), // '러' -- '러' FONTDATA_ITEM(368, 136, 136, fontpage_368_136_136), // '레' -- '레' FONTDATA_ITEM(368, 165, 165, fontpage_368_165_165), // '력' -- '력' FONTDATA_ITEM(368, 220, 220, fontpage_368_220_220), // '로' -- '로' FONTDATA_ITEM(369, 204, 204, fontpage_369_204_204), // '료' -- '료' FONTDATA_ITEM(370, 244, 244, fontpage_370_244_244), // '르' -- '르' FONTDATA_ITEM(371, 172, 172, fontpage_371_172_172), // '리' -- '리' + FONTDATA_ITEM(371, 176, 176, fontpage_371_176_176), // '린' -- '린' FONTDATA_ITEM(371, 189, 189, fontpage_371_189_189), // '립' -- '립' FONTDATA_ITEM(371, 193, 193, fontpage_371_193_193), // '링' -- '링' - FONTDATA_ITEM(371, 204, 204, fontpage_371_204_204), // '만' -- '만' FONTDATA_ITEM(372, 200, 200, fontpage_372_200_200), // '멈' -- '멈' FONTDATA_ITEM(372, 212, 212, fontpage_372_212_212), // '메' -- '메' FONTDATA_ITEM(372, 244, 244, fontpage_372_244_244), // '면' -- '면' FONTDATA_ITEM(373, 168, 168, fontpage_373_168_168), // '모' -- '모' + FONTDATA_ITEM(373, 187, 187, fontpage_373_187_187), // '못' -- '못' + FONTDATA_ITEM(375, 248, 248, fontpage_375_248_248), // '미' -- '미' FONTDATA_ITEM(376, 128, 128, fontpage_376_128_128), // '밀' -- '밀' FONTDATA_ITEM(376, 148, 148, fontpage_376_148_148), // '바' -- '바' FONTDATA_ITEM(377, 132, 132, fontpage_377_132_132), // '버' -- '버' FONTDATA_ITEM(377, 160, 160, fontpage_377_160_160), // '베' -- '베' FONTDATA_ITEM(377, 168, 168, fontpage_377_168_168), // '벨' -- '벨' - FONTDATA_ITEM(380, 140, 140, fontpage_380_140_140), // '브' -- '브' + FONTDATA_ITEM(377, 248, 248, fontpage_377_248_248), // '본' -- '본' FONTDATA_ITEM(380, 196, 196, fontpage_380_196_196), // '비' -- '비' + FONTDATA_ITEM(385, 172, 172, fontpage_385_172_172), // '사' -- '사' FONTDATA_ITEM(385, 189, 189, fontpage_385_189_189), // '삽' -- '삽' FONTDATA_ITEM(385, 200, 200, fontpage_385_200_200), // '새' -- '새' FONTDATA_ITEM(386, 164, 164, fontpage_386_164_164), // '설' -- '설' - FONTDATA_ITEM(386, 216, 216, fontpage_386_216_216), // '션' -- '션' FONTDATA_ITEM(387, 140, 141, fontpage_387_140_141), // '소' -- '속' FONTDATA_ITEM(389, 164, 164, fontpage_389_164_164), // '스' -- '스' FONTDATA_ITEM(389, 172, 172, fontpage_389_172_172), // '슬' -- '슬' @@ -495,6 +510,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(398, 252, 253, fontpage_398_252_253), // '일' -- '읽' FONTDATA_ITEM(399, 133, 133, fontpage_399_133_133), // '입' -- '입' FONTDATA_ITEM(399, 144, 145, fontpage_399_144_145), // '자' -- '작' + FONTDATA_ITEM(399, 152, 152, fontpage_399_152_152), // '잘' -- '잘' FONTDATA_ITEM(399, 165, 165, fontpage_399_165_165), // '장' -- '장' FONTDATA_ITEM(399, 172, 172, fontpage_399_172_172), // '재' -- '재' FONTDATA_ITEM(400, 128, 128, fontpage_400_128_128), // '저' -- '저' @@ -515,7 +531,6 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(412, 216, 216, fontpage_412_216_216), // '치' -- '치' FONTDATA_ITEM(412, 232, 232, fontpage_412_232_232), // '침' -- '침' FONTDATA_ITEM(412, 244, 244, fontpage_412_244_244), // '카' -- '카' - FONTDATA_ITEM(413, 152, 152, fontpage_413_152_152), // '캘' -- '캘' FONTDATA_ITEM(414, 156, 156, fontpage_414_156_156), // '켜' -- '켜' FONTDATA_ITEM(417, 209, 209, fontpage_417_209_209), // '탑' -- '탑' FONTDATA_ITEM(418, 176, 176, fontpage_418_176_176), // '터' -- '터' diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h index 0cc607468e..9a41b13a5a 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h @@ -5,32 +5,33 @@ */ #include -const u8g_fntpgm_uint8_t fontpage_2_133_133[30] U8G_FONT_SECTION("fontpage_2_133_133") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x05,0xfe,0x00, - 0x00,0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x08,0x78,0x88,0x78,0x20,0x30}; +const u8g_fntpgm_uint8_t fontpage_2_132_133[45] U8G_FONT_SECTION("fontpage_2_132_133") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x85,0x00,0x07,0xfe,0x00, + 0x00,0x05,0x09,0x09,0x06,0x00,0xfe,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x10,0x08, + 0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x08,0x78,0x88,0x78,0x20,0x30}; const u8g_fntpgm_uint8_t fontpage_2_135_135[31] U8G_FONT_SECTION("fontpage_2_135_135") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x80,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_2_153_153[30] U8G_FONT_SECTION("fontpage_2_153_153") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x05,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x05,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0xf0,0x80,0x70,0x20,0x30}; const u8g_fntpgm_uint8_t fontpage_2_193_196[73] U8G_FONT_SECTION("fontpage_2_193_196") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xc4,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xc4,0x00,0x0a,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0x40,0x60,0xc0,0x40,0x40,0x78,0x03,0x07, 0x07,0x06,0x01,0x00,0xc0,0x40,0x60,0xc0,0x40,0x40,0xe0,0x05,0x0a,0x0a,0x06,0x00, 0x00,0x10,0x20,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88,0x05,0x08,0x08,0x06,0x00, 0x00,0x10,0x20,0x00,0xb0,0xc8,0x88,0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_2_218_219[47] U8G_FONT_SECTION("fontpage_2_218_219") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xda,0xdb,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xda,0xdb,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x80,0x70,0x08,0x88, 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x78,0x80,0x70,0x08,0xf0}; const u8g_fntpgm_uint8_t fontpage_2_252_252[30] U8G_FONT_SECTION("fontpage_2_252_252") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfc,0xfc,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfc,0xfc,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x00,0xf8,0x10,0x20,0x40,0xf8}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 133, 133, fontpage_2_133_133), // 'ą' -- 'ą' + FONTDATA_ITEM(2, 132, 133, fontpage_2_132_133), // 'Ą' -- 'ą' FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' FONTDATA_ITEM(2, 153, 153, fontpage_2_153_153), // 'ę' -- 'ę' FONTDATA_ITEM(2, 193, 196, fontpage_2_193_196), // 'Ł' -- 'ń' diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h index 85a0bde3ab..cd0efda12f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h @@ -6,7 +6,7 @@ #include const u8g_fntpgm_uint8_t fontpage_8_144_152[135] U8G_FONT_SECTION("fontpage_8_144_152") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x98,0x00,0x07,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x98,0x00,0x07,0xff,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x80,0x80,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, 0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80, @@ -16,7 +16,7 @@ const u8g_fntpgm_uint8_t fontpage_8_144_152[135] U8G_FONT_SECTION("fontpage_8_14 0x06,0x00,0x00,0x70,0x88,0x08,0x70,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00, 0x88,0x88,0x98,0xa8,0xc8,0x88,0x88}; const u8g_fntpgm_uint8_t fontpage_8_154_168[214] U8G_FONT_SECTION("fontpage_8_154_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0xa8,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0xa8,0x00,0x07,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0,0xc0,0xa0,0x90,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x48,0x48,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88, @@ -31,12 +31,12 @@ const u8g_fntpgm_uint8_t fontpage_8_154_168[214] U8G_FONT_SECTION("fontpage_8_15 0x00,0x00,0x88,0x88,0x88,0x78,0x08,0x08,0x08,0x05,0x07,0x07,0x06,0x00,0x00,0xa8, 0xa8,0xa8,0xa8,0xa8,0xa8,0xf8}; const u8g_fntpgm_uint8_t fontpage_8_171_173[56] U8G_FONT_SECTION("fontpage_8_171_173") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xad,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xad,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xc8,0xa8,0xa8,0xc8,0x04,0x07, 0x07,0x06,0x01,0x00,0x80,0x80,0x80,0xe0,0x90,0x90,0xe0,0x05,0x07,0x07,0x06,0x00, 0x00,0x70,0x88,0x08,0x78,0x08,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_8_175_201[334] U8G_FONT_SECTION("fontpage_8_175_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xc9,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xc9,0x00,0x08,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x78,0x88,0x88,0x78,0x28,0x48,0x88,0x05,0x05, 0x05,0x06,0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x70, 0x80,0xf0,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf0,0x88,0xf0,0x88, @@ -58,13 +58,13 @@ const u8g_fntpgm_uint8_t fontpage_8_175_201[334] U8G_FONT_SECTION("fontpage_8_17 0x00,0x88,0x88,0x78,0x08,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8, 0xf8,0x05,0x07,0x07,0x06,0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xf8,0x08,0x08}; const u8g_fntpgm_uint8_t fontpage_8_203_207[72] U8G_FONT_SECTION("fontpage_8_203_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcf,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcf,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0xc8,0x04,0x05,0x05,0x06, 0x01,0x00,0x80,0x80,0xe0,0x90,0xe0,0x04,0x05,0x05,0x06,0x01,0x00,0xe0,0x10,0x70, 0x10,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0x90,0xa8,0xe8,0xa8,0x90,0x04,0x05,0x05, 0x06,0x01,0x00,0x70,0x90,0x70,0x50,0x90}; const u8g_fntpgm_uint8_t fontpage_8_209_209[30] U8G_FONT_SECTION("fontpage_8_209_209") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0xf0,0x80,0x70}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h index a75fa2c926..b069b351d7 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h @@ -6,51 +6,38 @@ #include const u8g_fntpgm_uint8_t fontpage_2_140_143[79] U8G_FONT_SECTION("fontpage_2_140_143") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8f,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8f,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x80,0x80,0x88, 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x88,0x70,0x05, 0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0xf0,0x48,0x48,0x48,0x48,0x48,0xf0,0x06, 0x0a,0x0a,0x06,0x00,0x00,0x14,0x08,0x00,0x08,0x08,0x78,0x88,0x88,0x88,0x78}; -const u8g_fntpgm_uint8_t fontpage_2_185_186[49] U8G_FONT_SECTION("fontpage_2_185_186") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xba,0x00,0x0a,0x00,0x00, - 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0x80,0x80,0x80,0x80,0x80,0x80, - 0xf8,0x03,0x0a,0x0a,0x06,0x01,0x00,0x20,0x40,0x00,0xc0,0x40,0x40,0x40,0x40,0x40, - 0xe0}; -const u8g_fntpgm_uint8_t fontpage_2_189_190[49] U8G_FONT_SECTION("fontpage_2_189_190") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbe,0x00,0x0a,0x00,0x00, - 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x80,0x80,0x80,0x80,0x80,0x80, - 0xf8,0x03,0x0a,0x0a,0x06,0x01,0x00,0xa0,0x40,0x00,0xc0,0x40,0x40,0x40,0x40,0x40, +const u8g_fntpgm_uint8_t fontpage_2_186_186[33] U8G_FONT_SECTION("fontpage_2_186_186") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0x00,0x00, + 0x00,0x03,0x0a,0x0a,0x06,0x01,0x00,0x20,0x40,0x00,0xc0,0x40,0x40,0x40,0x40,0x40, 0xe0}; const u8g_fntpgm_uint8_t fontpage_2_199_200[47] U8G_FONT_SECTION("fontpage_2_199_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc8,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc8,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88, 0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xb0,0xc8,0x88,0x88,0x88}; -const u8g_fntpgm_uint8_t fontpage_2_212_213[47] U8G_FONT_SECTION("fontpage_2_212_213") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd5,0x00,0x0a,0x00,0x00, - 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0xf0,0x88,0x88,0xf0,0xa0,0x90, - 0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0xb0,0xc8,0x80,0x80,0x80}; const u8g_fntpgm_uint8_t fontpage_2_224_225[47] U8G_FONT_SECTION("fontpage_2_224_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe1,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe1,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x70,0x88,0x80,0x70,0x08,0x88, 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0x78,0x80,0x70,0x08,0xf0}; -const u8g_fntpgm_uint8_t fontpage_2_228_229[49] U8G_FONT_SECTION("fontpage_2_228_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe5,0x00,0x0a,0x00,0x00, - 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x20,0x20,0x20,0x20,0x20, - 0x20,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x20,0x20,0xf8,0x20,0x20,0x20, +const u8g_fntpgm_uint8_t fontpage_2_229_229[33] U8G_FONT_SECTION("fontpage_2_229_229") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0x00,0x00, + 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0x20,0x20,0xf8,0x20,0x20,0x20, 0x18}; const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253_254") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfe,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfe,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x08,0x10,0x20,0x40,0x80, 0xf8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xf8,0x10,0x20,0x40,0xf8}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(2, 140, 143, fontpage_2_140_143), // 'Č' -- 'ď' - FONTDATA_ITEM(2, 185, 186, fontpage_2_185_186), // 'Ĺ' -- 'ĺ' - FONTDATA_ITEM(2, 189, 190, fontpage_2_189_190), // 'Ľ' -- 'ľ' + FONTDATA_ITEM(2, 186, 186, fontpage_2_186_186), // 'ĺ' -- 'ĺ' FONTDATA_ITEM(2, 199, 200, fontpage_2_199_200), // 'Ň' -- 'ň' - FONTDATA_ITEM(2, 212, 213, fontpage_2_212_213), // 'Ŕ' -- 'ŕ' FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' - FONTDATA_ITEM(2, 228, 229, fontpage_2_228_229), // 'Ť' -- 'ť' + FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_test.h b/Marlin/src/lcd/dogm/fontdata/langdata_test.h index 033188359d..85a3cf5553 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_test.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_test.h @@ -6,7 +6,7 @@ #include const u8g_fntpgm_uint8_t fontpage_8_128_255[1677] U8G_FONT_SECTION("fontpage_8_128_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0xff,0x00,0x0a,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0xff,0x00,0x0a,0xfe,0x00, 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x20,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80, 0xf8,0x05,0x09,0x09,0x06,0x00,0x00,0x50,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8, 0x05,0x09,0x09,0x06,0x00,0xfe,0xe0,0x40,0x40,0x70,0x48,0x48,0x48,0x08,0x30,0x05, @@ -111,8 +111,8 @@ const u8g_fntpgm_uint8_t fontpage_8_128_255[1677] U8G_FONT_SECTION("fontpage_8_1 0xa8,0x50,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x00,0x20,0xa8,0x88,0xa8,0x50,0x05, 0x0a,0x0a,0x06,0x00,0x00,0xf8,0xa8,0x00,0x50,0x88,0x88,0xa8,0xa8,0xa8,0x50,0x05, 0x08,0x08,0x06,0x00,0x00,0xf8,0xa8,0x00,0x50,0x88,0xa8,0xa8,0x50}; -const u8g_fntpgm_uint8_t fontpage_97_129_191[870] U8G_FONT_SECTION("fontpage_97_129_191") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x81,0xbf,0x00,0x0a,0xff,0x00, +const u8g_fntpgm_uint8_t fontpage_97_129_191[911] U8G_FONT_SECTION("fontpage_97_129_191") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x81,0xbf,0x00,0x0d,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x04,0x00,0x4e,0x00,0x55,0x00,0x64, 0x80,0x48,0x40,0xa8,0x40,0x90,0x40,0x90,0x80,0x61,0x00,0x06,0x00,0x08,0x0b,0x0b, 0x0c,0x01,0xff,0x20,0x10,0x70,0x1c,0x28,0xe2,0x39,0x21,0x21,0x12,0x0c,0x08,0x07, @@ -140,82 +140,88 @@ const u8g_fntpgm_uint8_t fontpage_97_129_191[870] U8G_FONT_SECTION("fontpage_97_ 0x1f,0x00,0x0a,0x0a,0x14,0x0c,0x01,0xff,0x10,0x00,0x08,0x00,0x08,0x00,0x10,0x00, 0x10,0x00,0x38,0x00,0x24,0x00,0x44,0x40,0x44,0x80,0x83,0x00,0x0a,0x0b,0x16,0x0c, 0x00,0xff,0x10,0x00,0x0c,0x80,0x00,0x40,0x1d,0x00,0xe2,0x80,0x02,0x00,0x02,0x00, - 0x04,0x00,0x04,0x00,0x08,0x00,0x10,0x00,0xff,0xff,0xff,0xff,0x04,0x03,0x03,0x0c, - 0x00,0x07,0x20,0x90,0x40,0xff,0x04,0x03,0x03,0x0c,0x00,0x06,0x20,0x90,0x40,0x03, - 0x03,0x03,0x0c,0x00,0x06,0x40,0xa0,0x40,0xff,0xff,0xff,0x05,0x03,0x03,0x06,0x00, - 0x01,0xf8,0x00,0xf8,0x04,0x04,0x04,0x06,0x00,0x00,0xf0,0x10,0x60,0x40,0x05,0x06, - 0x06,0x06,0x00,0x00,0xf8,0x08,0x28,0x30,0x20,0x40,0x03,0x04,0x04,0x06,0x01,0x00, - 0x20,0x40,0xc0,0x40,0x04,0x06,0x06,0x06,0x00,0x00,0x10,0x20,0x60,0xa0,0x20,0x20, - 0x04,0x04,0x04,0x06,0x00,0x00,0x20,0xf0,0x90,0x20,0x05,0x06,0x06,0x06,0x00,0x00, - 0x20,0xf8,0x88,0x08,0x10,0x20,0x03,0x04,0x04,0x06,0x01,0x00,0xe0,0x40,0x40,0xe0, - 0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0xf8,0x04,0x04,0x04,0x06,0x00, - 0x00,0x20,0xf0,0x60,0xa0,0x05,0x06,0x06,0x06,0x00,0x00,0x10,0xf8,0x30,0x50,0x90, - 0x10,0x05,0x06,0x06,0x06,0x00,0x00,0x40,0xf8,0x48,0x48,0x48,0x90,0x05,0x08,0x08, - 0x06,0x00,0x00,0x28,0x00,0x40,0xf8,0x48,0x48,0x48,0x90,0x05,0x06,0x06,0x06,0x00, - 0x00,0x20,0xf8,0x20,0xf8,0x20,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x28,0x00,0x20, - 0xf8,0x20,0xf8,0x20,0x20,0x04,0x05,0x05,0x06,0x00,0x00,0x70,0x90,0x10,0x20,0xc0, - 0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0x70,0x90,0x10,0x20,0xc0,0x05,0x06,0x06, - 0x06,0x00,0x00,0x40,0x78,0x90,0x10,0x10,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x28, - 0x00,0x40,0x78,0x90,0x10,0x10,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x08,0x08, - 0x08,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0xf8,0x08,0x08,0x08,0xf8,0x05, - 0x06,0x06,0x06,0x00,0x00,0x50,0xf8,0x50,0x10,0x20,0x40,0x05,0x08,0x08,0x06,0x00, - 0x00,0x28,0x00,0x50,0xf8,0x50,0x10,0x20,0x40,0x05,0x05,0x05,0x06,0x00,0x00,0xc0, - 0x08,0xc8,0x10,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0xc0,0x08,0xc8,0x10, - 0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x10,0x20,0x50,0x88,0x05,0x07,0x07,0x06, - 0x00,0x00,0x28,0x00,0xf8,0x10,0x20,0x50,0x88,0x05,0x06,0x06,0x06,0x00,0x00,0x40, - 0xf8,0x48,0x50,0x40,0x38,0x05,0x08,0x08,0x06,0x00,0x00,0x28,0x00,0x40,0xf8,0x48, - 0x50,0x40,0x38,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0x48,0x10,0x60,0x05,0x07, - 0x07,0x06,0x00,0x00,0x28,0x00,0x88,0x88,0x48,0x10,0x60,0x05,0x05,0x05,0x06,0x00, - 0x00,0x78,0x48,0xa8,0x10,0x60}; -const u8g_fntpgm_uint8_t fontpage_97_193_255[753] U8G_FONT_SECTION("fontpage_97_193_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xff,0x00,0x08,0x00,0x00, - 0x00,0x05,0x06,0x06,0x06,0x00,0x00,0x10,0xe0,0x20,0xf8,0x20,0x40,0x05,0x08,0x08, - 0x06,0x00,0x00,0x28,0x00,0x10,0xe0,0x20,0xf8,0x20,0x40,0x05,0x04,0x04,0x06,0x00, - 0x00,0xa8,0xa8,0x08,0x30,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0xa8,0x08,0x10,0x20, - 0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0xa8,0xa8,0x08,0x10,0x20,0x05,0x06,0x06, - 0x06,0x00,0x00,0x70,0x00,0xf8,0x20,0x20,0x40,0x05,0x08,0x08,0x06,0x00,0x00,0x28, - 0x00,0x70,0x00,0xf8,0x20,0x20,0x40,0x03,0x06,0x06,0x06,0x01,0x00,0x80,0x80,0xc0, - 0xa0,0x80,0x80,0x04,0x08,0x08,0x06,0x01,0x00,0x50,0x00,0x80,0x80,0xc0,0xa0,0x80, - 0x80,0x05,0x06,0x06,0x06,0x00,0x00,0x20,0xf8,0x20,0x20,0x40,0x80,0x05,0x05,0x05, - 0x06,0x00,0x00,0x70,0x00,0x00,0x00,0xf8,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x08, - 0x50,0x20,0xd0,0x05,0x06,0x06,0x06,0x00,0x00,0x20,0xf8,0x10,0x20,0x70,0xa8,0x03, - 0x06,0x06,0x06,0x01,0x00,0x20,0x20,0x20,0x20,0x40,0x80,0x05,0x05,0x05,0x06,0x00, - 0x00,0x10,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0x10,0x88, - 0x88,0x88,0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x18,0x18,0x00,0x10,0x88,0x88,0x88, - 0x88,0x05,0x06,0x06,0x06,0x00,0x00,0x80,0x80,0xf8,0x80,0x80,0x78,0x05,0x07,0x07, - 0x06,0x00,0x00,0x28,0x80,0x80,0xf8,0x80,0x80,0x78,0x05,0x07,0x07,0x06,0x00,0x00, - 0x18,0x98,0x80,0xf8,0x80,0x80,0x78,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x08,0x08, - 0x10,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0xf8,0x08,0x08,0x10,0x60,0x05, - 0x08,0x08,0x06,0x00,0x00,0x18,0x18,0x00,0xf8,0x08,0x08,0x10,0x60,0x05,0x04,0x04, - 0x06,0x00,0x01,0x40,0xa0,0x10,0x08,0x05,0x06,0x06,0x06,0x00,0x01,0x28,0x00,0x40, - 0xa0,0x10,0x08,0x05,0x06,0x06,0x06,0x00,0x01,0x18,0x18,0x40,0xa0,0x10,0x08,0x05, - 0x06,0x06,0x06,0x00,0x00,0x20,0xf8,0x20,0xa8,0xa8,0x20,0x05,0x08,0x08,0x06,0x00, - 0x00,0x28,0x00,0x20,0xf8,0x20,0xa8,0xa8,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x18, - 0x18,0x20,0xf8,0x20,0xa8,0xa8,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x08,0x50, - 0x20,0x10,0x04,0x05,0x05,0x06,0x01,0x00,0xe0,0x00,0xe0,0x00,0xf0,0x05,0x05,0x05, - 0x06,0x00,0x00,0x20,0x40,0x88,0xf8,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0x08,0x28, - 0x10,0x28,0xc0,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x40,0xf8,0x40,0x38,0x05,0x04, - 0x04,0x06,0x00,0x00,0x40,0xf8,0x50,0x40,0x05,0x06,0x06,0x06,0x00,0x00,0x40,0xf8, - 0x48,0x50,0x40,0x40,0x04,0x04,0x04,0x06,0x00,0x00,0x60,0x20,0x20,0xf0,0x05,0x05, - 0x05,0x06,0x00,0x00,0x70,0x10,0x10,0x10,0xf8,0x04,0x05,0x05,0x06,0x00,0x00,0xf0, - 0x10,0xf0,0x10,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x08,0xf8,0x08,0xf8,0x05, - 0x06,0x06,0x06,0x00,0x00,0x70,0x00,0xf8,0x08,0x10,0x20,0x04,0x06,0x06,0x06,0x00, - 0x00,0x90,0x90,0x90,0x90,0x10,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x20,0xa0,0xa8, - 0xa8,0xb0,0x04,0x05,0x05,0x06,0x00,0x00,0x80,0x80,0x90,0xa0,0xc0,0x05,0x05,0x05, - 0x06,0x00,0x00,0xf8,0x88,0x88,0x88,0xf8,0x04,0x04,0x04,0x06,0x00,0x00,0xf0,0x90, - 0x10,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x88,0x08,0x10,0x20,0x05,0x06,0x06, - 0x06,0x00,0x00,0x10,0xf8,0x50,0x50,0xf8,0x10,0x05,0x05,0x05,0x06,0x00,0x00,0xf8, - 0x08,0x30,0x20,0xf8,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x08,0xf8,0x08,0x30,0x05, - 0x05,0x05,0x06,0x00,0x00,0xc0,0x08,0x08,0x10,0xe0,0x05,0x08,0x08,0x06,0x00,0x00, - 0x28,0x00,0x20,0xf8,0x88,0x08,0x10,0x20,0x04,0x04,0x04,0x06,0x00,0x00,0x40,0xf0, - 0x50,0xa0,0x04,0x04,0x04,0x06,0x00,0x00,0x40,0xf0,0x20,0x40,0x05,0x07,0x07,0x06, - 0x00,0x00,0x28,0x00,0xf8,0x88,0x08,0x10,0x60,0x05,0x08,0x08,0x06,0x00,0x00,0x28, - 0x00,0x10,0xf8,0x50,0x50,0xf8,0x10,0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0xf8, - 0x08,0x30,0x20,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x28,0x00,0xf8,0x08,0xf8,0x08, - 0x30,0x02,0x02,0x02,0x06,0x02,0x02,0xc0,0xc0,0x05,0x01,0x01,0x06,0x00,0x02,0xf8, - 0x05,0x04,0x04,0x06,0x00,0x01,0x80,0x60,0x10,0x08,0x05,0x05,0x05,0x06,0x00,0x01, - 0x28,0x80,0x60,0x10,0x08,0x05,0x06,0x06,0x06,0x00,0x00,0xf8,0x08,0x08,0x08,0x08, - 0x08}; + 0x04,0x00,0x04,0x00,0x08,0x00,0x10,0x00,0xff,0xff,0xff,0xff,0x04,0x03,0x03,0x06, + 0x00,0x05,0x20,0x90,0x40,0xff,0x04,0x03,0x03,0x06,0x00,0x05,0x20,0x90,0x40,0x03, + 0x03,0x03,0x06,0x00,0x05,0x40,0xa0,0x40,0xff,0xff,0xff,0x05,0x03,0x03,0x06,0x00, + 0x03,0xf8,0x00,0xf8,0x04,0x05,0x05,0x06,0x00,0x00,0xf0,0x10,0x60,0x40,0x80,0x05, + 0x07,0x07,0x06,0x00,0x00,0xf8,0x08,0x28,0x30,0x20,0x20,0x40,0x04,0x05,0x05,0x06, + 0x00,0x00,0x10,0x20,0x60,0xa0,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x08,0x10,0x20, + 0x60,0xa0,0x20,0x20,0x04,0x05,0x05,0x06,0x00,0x00,0x20,0xf0,0x90,0x10,0x20,0x05, + 0x07,0x07,0x06,0x00,0x00,0x20,0xf8,0x88,0x88,0x08,0x10,0x60,0x03,0x04,0x04,0x06, + 0x00,0x00,0xe0,0x40,0x40,0xe0,0x05,0x06,0x06,0x06,0x00,0x00,0xf8,0x20,0x20,0x20, + 0x20,0xf8,0x04,0x05,0x05,0x06,0x00,0x00,0x20,0xf0,0x20,0x60,0xa0,0x05,0x07,0x07, + 0x06,0x00,0x00,0x10,0xf8,0x10,0x30,0x50,0x90,0x10,0x05,0x07,0x07,0x06,0x00,0x00, + 0x40,0xf8,0x48,0x48,0x48,0x48,0x98,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x40, + 0xf8,0x48,0x48,0x48,0x48,0x98,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0xf8,0x20,0x20, + 0xf8,0x10,0x10,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x20,0xf8,0x20,0x20,0xf8, + 0x10,0x10,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0x78,0x48,0x88,0x08,0x10,0x60,0x05, + 0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x40,0x78,0x48,0x88,0x08,0x10,0x60,0x05,0x07, + 0x07,0x06,0x00,0x00,0x80,0xf8,0x90,0x90,0x10,0x10,0x20,0x05,0x09,0x09,0x06,0x00, + 0x00,0x28,0x28,0x80,0xf8,0x90,0x90,0x10,0x10,0x20,0x05,0x06,0x06,0x06,0x00,0x00, + 0xf8,0x08,0x08,0x08,0x08,0xf8,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00,0xf8, + 0x08,0x08,0x08,0x08,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0xf8,0x50,0x50,0x50, + 0x10,0x20,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x50,0xf8,0x50,0x50,0x50,0x10, + 0x20,0x05,0x06,0x06,0x06,0x00,0x00,0xc0,0x08,0xc8,0x08,0x10,0xe0,0x07,0x0d,0x0d, + 0x06,0x00,0x00,0x02,0x00,0x00,0x00,0x28,0x28,0x00,0xc0,0x08,0xc8,0x08,0x10,0xe0, + 0x05,0x06,0x06,0x06,0x00,0x00,0x70,0x10,0x10,0x20,0x50,0x88,0x05,0x09,0x09,0x06, + 0x00,0x00,0x28,0x28,0x00,0x70,0x10,0x10,0x20,0x50,0x88,0x05,0x07,0x07,0x06,0x00, + 0x00,0x40,0x40,0xf8,0x48,0x50,0x40,0x38,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x08, + 0x40,0x40,0xf8,0x48,0x50,0x40,0x38,0x05,0x06,0x06,0x06,0x00,0x00,0x88,0x48,0x48, + 0x10,0x10,0x20,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00,0x88,0x48,0x48,0x10, + 0x10,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0x78,0x48,0xa8,0x18,0x10,0x60}; +const u8g_fntpgm_uint8_t fontpage_97_193_255[822] U8G_FONT_SECTION("fontpage_97_193_255") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xff,0x00,0x09,0x00,0x00, + 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x10,0x60,0x20,0xf8,0x20,0x20,0x40,0x05,0x09, + 0x09,0x06,0x00,0x00,0x28,0x08,0x10,0x60,0x20,0xf8,0x20,0x20,0x40,0x05,0x04,0x04, + 0x06,0x00,0x00,0xa8,0xa8,0x08,0x30,0x05,0x06,0x06,0x06,0x00,0x00,0xa8,0xa8,0xa8, + 0x08,0x10,0x60,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00,0xa8,0xa8,0xa8,0x08, + 0x10,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x00,0xf8,0x20,0x20,0x20,0x40,0x05, + 0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x70,0x00,0xf8,0x20,0x20,0x20,0x40,0x04,0x07, + 0x07,0x06,0x01,0x00,0x80,0x80,0xc0,0xa0,0x90,0x80,0x80,0x04,0x09,0x09,0x06,0x01, + 0x00,0x50,0x10,0x80,0x80,0xc0,0xa0,0x90,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00, + 0x20,0x20,0xf8,0x20,0x20,0x40,0x80,0x05,0x06,0x06,0x06,0x00,0x00,0x70,0x00,0x00, + 0x00,0x00,0xf8,0x05,0x06,0x06,0x06,0x00,0x00,0x78,0x08,0x28,0x10,0x28,0xc0,0x05, + 0x07,0x07,0x06,0x00,0x00,0x20,0x70,0x10,0x20,0x70,0xa8,0x20,0x03,0x06,0x06,0x06, + 0x01,0x00,0x20,0x20,0x20,0x40,0x40,0x80,0x05,0x06,0x06,0x06,0x00,0x00,0x10,0x50, + 0x50,0x48,0x88,0x88,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00,0x10,0x50,0x50, + 0x48,0x88,0x88,0x05,0x09,0x09,0x06,0x00,0x00,0x18,0x18,0x00,0x10,0x50,0x50,0x48, + 0x88,0x88,0x04,0x06,0x06,0x06,0x00,0x00,0x80,0x90,0xe0,0x80,0x80,0x70,0x05,0x09, + 0x09,0x06,0x00,0x00,0x28,0x28,0x00,0x80,0x90,0xe0,0x80,0x80,0x70,0x05,0x09,0x09, + 0x06,0x00,0x00,0x18,0x18,0x00,0x80,0x90,0xe0,0x80,0x80,0x70,0x05,0x06,0x06,0x06, + 0x00,0x00,0xf8,0x08,0x08,0x08,0x10,0x60,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28, + 0x00,0xf8,0x08,0x08,0x08,0x10,0x60,0x05,0x09,0x09,0x06,0x00,0x00,0x18,0x18,0x00, + 0xf8,0x08,0x08,0x08,0x10,0x60,0x05,0x05,0x05,0x06,0x00,0x01,0x60,0xa0,0x10,0x10, + 0x08,0x05,0x08,0x08,0x06,0x00,0x01,0x28,0x28,0x00,0x60,0xa0,0x10,0x10,0x08,0x05, + 0x08,0x08,0x06,0x00,0x01,0x18,0x18,0x00,0x60,0xa0,0x10,0x10,0x08,0x05,0x07,0x07, + 0x06,0x00,0x00,0x20,0xf8,0x20,0xa8,0xa8,0xa8,0x20,0x05,0x09,0x09,0x06,0x00,0x00, + 0x28,0x08,0x20,0xf8,0x20,0xa8,0xa8,0xa8,0x20,0x05,0x09,0x09,0x06,0x00,0x00,0x18, + 0x18,0x20,0xf8,0x20,0xa8,0xa8,0xa8,0x20,0x05,0x06,0x06,0x06,0x00,0x00,0xf8,0x08, + 0x08,0x50,0x20,0x10,0x04,0x06,0x06,0x06,0x01,0x00,0xe0,0x00,0xe0,0x00,0xc0,0x30, + 0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0x20,0x40,0x48,0xf8,0x08,0x05,0x06,0x06, + 0x06,0x00,0x00,0x08,0x48,0x30,0x10,0x28,0xc0,0x05,0x06,0x06,0x06,0x00,0x00,0xf0, + 0x40,0xf8,0x40,0x40,0x38,0x05,0x05,0x05,0x06,0x00,0x00,0x40,0xf8,0x48,0x50,0x40, + 0x05,0x07,0x07,0x06,0x00,0x00,0x40,0x40,0xf8,0x48,0x50,0x40,0x40,0x04,0x05,0x05, + 0x06,0x00,0x00,0x60,0x20,0x20,0x20,0xf0,0x05,0x06,0x06,0x06,0x00,0x00,0x70,0x10, + 0x10,0x10,0x10,0xf8,0x04,0x05,0x05,0x06,0x00,0x00,0xf0,0x10,0xf0,0x10,0xf0,0x05, + 0x06,0x06,0x06,0x00,0x00,0xf8,0x08,0xf8,0x08,0x08,0xf8,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x00,0xf8,0x08,0x08,0x10,0x60,0x04,0x07,0x07,0x06,0x00,0x00,0x10,0x90, + 0x90,0x90,0x90,0x10,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xa0,0xa0,0xa8, + 0xa8,0xb0,0x05,0x06,0x06,0x06,0x00,0x00,0x80,0x80,0x80,0x88,0xb0,0xc0,0x05,0x06, + 0x06,0x06,0x00,0x00,0xf8,0x88,0x88,0x88,0x88,0xf8,0x04,0x05,0x05,0x06,0x00,0x00, + 0xf0,0x90,0x10,0x10,0x60,0x05,0x06,0x06,0x06,0x00,0x00,0xf8,0x88,0x88,0x08,0x10, + 0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x10,0xf8,0x50,0x50,0xf8,0x10,0x10,0x05,0x06, + 0x06,0x06,0x00,0x00,0x70,0x10,0x20,0x20,0x20,0xf8,0x05,0x06,0x06,0x06,0x00,0x00, + 0xf8,0x08,0xf8,0x08,0x10,0x60,0x05,0x06,0x06,0x06,0x00,0x00,0xc0,0x08,0x08,0x08, + 0x10,0xe0,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x20,0xf8,0x88,0x88,0x08,0x10, + 0x60,0x04,0x05,0x05,0x06,0x00,0x00,0x40,0xf0,0x50,0x50,0xb0,0x04,0x05,0x05,0x06, + 0x00,0x00,0x80,0xf0,0xa0,0x20,0x40,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00, + 0xf8,0x88,0x88,0x08,0x10,0x60,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x08,0x10,0xf8, + 0x50,0x50,0xf8,0x10,0x10,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00,0x70,0x10, + 0x20,0x20,0x20,0xf8,0x05,0x09,0x09,0x06,0x00,0x00,0x28,0x28,0x00,0xf8,0x08,0xf8, + 0x08,0x10,0x60,0x02,0x02,0x02,0x06,0x02,0x03,0xc0,0xc0,0x05,0x02,0x02,0x06,0x00, + 0x03,0x80,0x78,0x05,0x04,0x04,0x06,0x00,0x02,0x80,0x60,0x10,0x08,0x05,0x07,0x07, + 0x06,0x00,0x02,0x28,0x28,0x00,0x80,0x60,0x10,0x08,0x05,0x06,0x06,0x06,0x00,0x00, + 0xf8,0x08,0x08,0x08,0x08,0x08}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h index b85a19f547..454fc7cc67 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h @@ -5,22 +5,23 @@ */ #include -const u8g_fntpgm_uint8_t fontpage_2_159_159[33] U8G_FONT_SECTION("fontpage_2_159_159") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x08,0xfe,0x00, - 0x00,0x05,0x0a,0x0a,0x06,0x00,0xfe,0x88,0x70,0x00,0x70,0x88,0x88,0x88,0x78,0x08, +const u8g_fntpgm_uint8_t fontpage_2_158_159[49] U8G_FONT_SECTION("fontpage_2_158_159") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9e,0x9f,0x00,0x0a,0xfe,0x00, + 0x00,0x05,0x0a,0x0a,0x06,0x00,0x00,0x88,0x70,0x00,0x70,0x88,0x80,0x80,0x98,0x88, + 0x70,0x05,0x0a,0x0a,0x06,0x00,0xfe,0x88,0x70,0x00,0x70,0x88,0x88,0x88,0x78,0x08, 0x70}; const u8g_fntpgm_uint8_t fontpage_2_176_177[43] U8G_FONT_SECTION("fontpage_2_176_177") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb1,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb1,0x00,0x09,0x00,0x00, 0x00,0x03,0x09,0x09,0x06,0x01,0x00,0x40,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0, 0x03,0x05,0x05,0x06,0x01,0x00,0xc0,0x40,0x40,0x40,0xe0}; const u8g_fntpgm_uint8_t fontpage_2_222_223[45] U8G_FONT_SECTION("fontpage_2_222_223") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xdf,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xdf,0x00,0x07,0xfe,0x00, 0x00,0x05,0x09,0x09,0x06,0x00,0xfe,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x10,0x60, 0x05,0x07,0x07,0x06,0x00,0xfe,0x78,0x80,0x70,0x08,0xf0,0x10,0x60}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 159, 159, fontpage_2_159_159), // 'ğ' -- 'ğ' + FONTDATA_ITEM(2, 158, 159, fontpage_2_158_159), // 'Ğ' -- 'ğ' FONTDATA_ITEM(2, 176, 177, fontpage_2_176_177), // 'İ' -- 'ı' FONTDATA_ITEM(2, 222, 223, fontpage_2_222_223), // 'Ş' -- 'ş' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h index d6e8337fd8..5d34d1b994 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h @@ -6,25 +6,25 @@ #include const u8g_fntpgm_uint8_t fontpage_8_134_134[30] U8G_FONT_SECTION("fontpage_8_134_134") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x07,0x00,0x00, 0x00,0x03,0x07,0x07,0x06,0x01,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0}; const u8g_fntpgm_uint8_t fontpage_8_144_146[56] U8G_FONT_SECTION("fontpage_8_144_146") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x92,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x92,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x80,0x80,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, 0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0}; const u8g_fntpgm_uint8_t fontpage_8_148_149[44] U8G_FONT_SECTION("fontpage_8_148_149") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x94,0x95,0x00,0x07,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x94,0x95,0x00,0x07,0xff,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0xff,0x30,0x50,0x50,0x50,0x50,0x50,0xf8,0x88,0x05, 0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8}; const u8g_fntpgm_uint8_t fontpage_8_151_154[72] U8G_FONT_SECTION("fontpage_8_151_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x9a,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x9a,0x00,0x0a,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x08,0x70,0x08,0x88,0x70,0x05,0x07, 0x07,0x06,0x00,0x00,0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00, 0x00,0x88,0x70,0x00,0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0x88,0x90,0xa0,0xc0,0xa0,0x90,0x88}; const u8g_fntpgm_uint8_t fontpage_8_156_164[134] U8G_FONT_SECTION("fontpage_8_156_164") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0xa4,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0xa4,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x88, @@ -34,14 +34,14 @@ const u8g_fntpgm_uint8_t fontpage_8_156_164[134] U8G_FONT_SECTION("fontpage_8_15 0x00,0x00,0x88,0x88,0x88,0x88,0x78,0x08,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x20, 0x70,0xa8,0xa8,0xa8,0x70,0x20}; const u8g_fntpgm_uint8_t fontpage_8_166_166[32] U8G_FONT_SECTION("fontpage_8_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x07,0xfe,0x00, 0x00,0x05,0x09,0x09,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0x90,0x90,0xf8,0x08,0x08 }; const u8g_fntpgm_uint8_t fontpage_8_168_168[30] U8G_FONT_SECTION("fontpage_8_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8,0xa8,0xa8,0xf8}; const u8g_fntpgm_uint8_t fontpage_8_176_201[321] U8G_FONT_SECTION("fontpage_8_176_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xc9,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xc9,0x00,0x08,0xfe,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06, 0x00,0x00,0x70,0x80,0xf0,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf0, 0x88,0xf0,0x88,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x80,0x80,0x80,0x80,0x05, @@ -63,17 +63,17 @@ const u8g_fntpgm_uint8_t fontpage_8_176_201[321] U8G_FONT_SECTION("fontpage_8_17 0xa8,0xa8,0xa8,0xf8,0x05,0x07,0x07,0x06,0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xf8,0x08, 0x08}; const u8g_fntpgm_uint8_t fontpage_8_204_204[28] U8G_FONT_SECTION("fontpage_8_204_204") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x05,0x00,0x00, 0x00,0x04,0x05,0x05,0x06,0x01,0x00,0x80,0x80,0xe0,0x90,0xe0}; const u8g_fntpgm_uint8_t fontpage_8_206_207[39] U8G_FONT_SECTION("fontpage_8_206_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xcf,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xcf,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x90,0xa8,0xe8,0xa8,0x90,0x04,0x05,0x05,0x06, 0x01,0x00,0x70,0x90,0x70,0x50,0x90}; const u8g_fntpgm_uint8_t fontpage_8_212_212[28] U8G_FONT_SECTION("fontpage_8_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x05,0x00,0x00, 0x00,0x04,0x05,0x05,0x06,0x01,0x00,0x70,0x80,0xe0,0x80,0x70}; const u8g_fntpgm_uint8_t fontpage_8_214_214[29] U8G_FONT_SECTION("fontpage_8_214_214") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x06,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x06,0x00,0x00, 0x00,0x03,0x06,0x06,0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0xe0}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h index 7c309907cd..bebf3251c1 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h @@ -6,178 +6,174 @@ #include const u8g_fntpgm_uint8_t fontpage_2_131_131[31] U8G_FONT_SECTION("fontpage_2_131_131") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x88,0x70,0x00,0x70,0x08,0x78,0x88,0x78}; const u8g_fntpgm_uint8_t fontpage_2_144_145[44] U8G_FONT_SECTION("fontpage_2_144_145") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x91,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x91,0x00,0x08,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x48,0x48,0xe8,0x48,0x48,0xf0,0x06,0x08, 0x08,0x06,0x00,0x00,0x08,0x1c,0x08,0x78,0x88,0x88,0x88,0x78}; const u8g_fntpgm_uint8_t fontpage_2_169_169[31] U8G_FONT_SECTION("fontpage_2_169_169") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x08,0x00,0x00, 0x00,0x04,0x08,0x08,0x06,0x00,0x00,0x50,0xa0,0x00,0x60,0x20,0x20,0x20,0x70}; const u8g_fntpgm_uint8_t fontpage_3_161_161[30] U8G_FONT_SECTION("fontpage_3_161_161") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x07,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x08,0x08,0x70,0x88,0x88,0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_3_175_176[43] U8G_FONT_SECTION("fontpage_3_175_176") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xb0,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xb0,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x08,0x98,0x90,0x90,0x90,0x90,0x90,0x60,0x05, 0x06,0x06,0x06,0x00,0x00,0x08,0x98,0x90,0x90,0xb0,0x50}; const u8g_fntpgm_uint8_t fontpage_6_131_131[25] U8G_FONT_SECTION("fontpage_6_131_131") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x0a,0x00,0x00, 0x00,0x05,0x02,0x02,0x06,0x00,0x08,0x68,0xb0}; const u8g_fntpgm_uint8_t fontpage_6_137_137[26] U8G_FONT_SECTION("fontpage_6_137_137") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0x00,0x00, 0x00,0x03,0x03,0x03,0x06,0x01,0x07,0xc0,0x20,0x40}; const u8g_fntpgm_uint8_t fontpage_6_163_163[24] U8G_FONT_SECTION("fontpage_6_163_163") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa3,0x00,0x00,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa3,0x00,0x00,0xfe,0x00, 0x00,0x01,0x01,0x01,0x06,0x02,0xfe,0x80}; const u8g_fntpgm_uint8_t fontpage_6_192_193[33] U8G_FONT_SECTION("fontpage_6_192_193") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc1,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc1,0x00,0x0a,0x00,0x00, 0x00,0x02,0x02,0x02,0x06,0x01,0x08,0x80,0x40,0x02,0x02,0x02,0x06,0x02,0x08,0x40, 0x80}; const u8g_fntpgm_uint8_t fontpage_61_161_161[30] U8G_FONT_SECTION("fontpage_61_161_161") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x05,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x05,0xfe,0x00, 0x00,0x05,0x07,0x07,0x07,0x00,0xfe,0x70,0x08,0x78,0x88,0x78,0x00,0x20}; const u8g_fntpgm_uint8_t fontpage_61_163_163[32] U8G_FONT_SECTION("fontpage_61_163_163") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa3,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa3,0x00,0x09,0x00,0x00, 0x00,0x05,0x09,0x09,0x07,0x00,0x00,0x30,0x10,0x20,0x00,0x70,0x08,0x78,0x88,0x78 }; const u8g_fntpgm_uint8_t fontpage_61_165_165[33] U8G_FONT_SECTION("fontpage_61_165_165") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa5,0xa5,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa5,0xa5,0x00,0x0a,0x00,0x00, 0x00,0x06,0x0a,0x0a,0x07,0x00,0x00,0x04,0x08,0x30,0x48,0x00,0x70,0x08,0x78,0x88, 0x78}; const u8g_fntpgm_uint8_t fontpage_61_167_167[33] U8G_FONT_SECTION("fontpage_61_167_167") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x10,0x08,0x30,0x48,0x00,0x70,0x08,0x78,0x88, 0x78}; const u8g_fntpgm_uint8_t fontpage_61_169_169[34] U8G_FONT_SECTION("fontpage_61_169_169") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x0b,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x0b,0x00,0x00, 0x00,0x06,0x0b,0x0b,0x07,0x00,0x00,0x0c,0x04,0x08,0x30,0x48,0x00,0x70,0x08,0x78, 0x88,0x78}; const u8g_fntpgm_uint8_t fontpage_61_173_173[33] U8G_FONT_SECTION("fontpage_61_173_173") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x08,0xfe,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0xfe,0x30,0x48,0x00,0x70,0x08,0x78,0x88,0x78,0x00, 0x20}; const u8g_fntpgm_uint8_t fontpage_61_175_175[33] U8G_FONT_SECTION("fontpage_61_175_175") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x08,0x10,0x48,0x30,0x00,0x70,0x08,0x78,0x88, 0x78}; const u8g_fntpgm_uint8_t fontpage_61_177_177[33] U8G_FONT_SECTION("fontpage_61_177_177") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x40,0x20,0x48,0x30,0x00,0x70,0x08,0x78,0x88, 0x78}; const u8g_fntpgm_uint8_t fontpage_61_179_179[34] U8G_FONT_SECTION("fontpage_61_179_179") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb3,0xb3,0x00,0x0b,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb3,0xb3,0x00,0x0b,0x00,0x00, 0x00,0x05,0x0b,0x0b,0x07,0x00,0x00,0x18,0x08,0x10,0x48,0x30,0x00,0x70,0x08,0x78, 0x88,0x78}; const u8g_fntpgm_uint8_t fontpage_61_181_181[34] U8G_FONT_SECTION("fontpage_61_181_181") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb5,0xb5,0x00,0x0b,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb5,0xb5,0x00,0x0b,0x00,0x00, 0x00,0x06,0x0b,0x0b,0x07,0x00,0x00,0x14,0x28,0x00,0x48,0x30,0x00,0x70,0x08,0x78, 0x88,0x78}; const u8g_fntpgm_uint8_t fontpage_61_183_183[33] U8G_FONT_SECTION("fontpage_61_183_183") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x08,0xfe,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0xfe,0x48,0x30,0x00,0x70,0x08,0x78,0x88,0x78,0x00, 0x20}; -const u8g_fntpgm_uint8_t fontpage_61_187_187[32] U8G_FONT_SECTION("fontpage_61_187_187") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x09,0x00,0x00, - 0x00,0x05,0x09,0x09,0x07,0x00,0x00,0x30,0x10,0x20,0x00,0x70,0x88,0xf0,0x80,0x78 - }; const u8g_fntpgm_uint8_t fontpage_61_191_191[33] U8G_FONT_SECTION("fontpage_61_191_191") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x0a,0x00,0x00, 0x00,0x06,0x0a,0x0a,0x07,0x00,0x00,0x04,0x08,0x20,0x50,0x00,0x70,0x88,0xf0,0x80, 0x78}; const u8g_fntpgm_uint8_t fontpage_61_193_193[33] U8G_FONT_SECTION("fontpage_61_193_193") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xc1,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xc1,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x10,0x08,0x20,0x50,0x00,0x70,0x88,0xf0,0x80, 0x78}; const u8g_fntpgm_uint8_t fontpage_61_195_195[34] U8G_FONT_SECTION("fontpage_61_195_195") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0b,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0b,0x00,0x00, 0x00,0x05,0x0b,0x0b,0x07,0x00,0x00,0x18,0x08,0x10,0x60,0x90,0x00,0x60,0x90,0xf0, 0x80,0x70}; const u8g_fntpgm_uint8_t fontpage_61_199_199[33] U8G_FONT_SECTION("fontpage_61_199_199") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x08,0xfe,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0xfe,0x20,0x50,0x00,0x70,0x88,0xf0,0x80,0x78,0x00, 0x20}; const u8g_fntpgm_uint8_t fontpage_61_201_201[32] U8G_FONT_SECTION("fontpage_61_201_201") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x09,0x00,0x00, 0x00,0x03,0x09,0x09,0x07,0x02,0x00,0x60,0x20,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0 }; const u8g_fntpgm_uint8_t fontpage_61_203_203[32] U8G_FONT_SECTION("fontpage_61_203_203") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x07,0xfe,0x00, 0x00,0x03,0x09,0x09,0x07,0x02,0xfe,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0,0x00,0x40 }; const u8g_fntpgm_uint8_t fontpage_61_205_205[30] U8G_FONT_SECTION("fontpage_61_205_205") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x05,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x05,0xfe,0x00, 0x00,0x05,0x07,0x07,0x07,0x00,0xfe,0x70,0x88,0x88,0x88,0x70,0x00,0x20}; const u8g_fntpgm_uint8_t fontpage_61_207_207[32] U8G_FONT_SECTION("fontpage_61_207_207") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x09,0x00,0x00, 0x00,0x05,0x09,0x09,0x07,0x00,0x00,0x30,0x10,0x20,0x00,0x70,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_209_209[33] U8G_FONT_SECTION("fontpage_61_209_209") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0x00,0x00, 0x00,0x06,0x0a,0x0a,0x07,0x00,0x00,0x04,0x08,0x20,0x50,0x00,0x70,0x88,0x88,0x88, 0x70}; const u8g_fntpgm_uint8_t fontpage_61_211_211[33] U8G_FONT_SECTION("fontpage_61_211_211") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd3,0xd3,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd3,0xd3,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x10,0x08,0x20,0x50,0x00,0x70,0x88,0x88,0x88, 0x70}; const u8g_fntpgm_uint8_t fontpage_61_213_213[33] U8G_FONT_SECTION("fontpage_61_213_213") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x18,0x08,0x30,0x50,0x00,0x70,0x88,0x88,0x88, 0x70}; const u8g_fntpgm_uint8_t fontpage_61_215_215[34] U8G_FONT_SECTION("fontpage_61_215_215") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd7,0xd7,0x00,0x0b,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd7,0xd7,0x00,0x0b,0x00,0x00, 0x00,0x05,0x0b,0x0b,0x07,0x00,0x00,0x28,0x50,0x00,0x20,0x50,0x00,0x70,0x88,0x88, 0x88,0x70}; const u8g_fntpgm_uint8_t fontpage_61_217_217[33] U8G_FONT_SECTION("fontpage_61_217_217") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x08,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x08,0xfe,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0xfe,0x20,0x50,0x00,0x70,0x88,0x88,0x88,0x70,0x00, 0x20}; const u8g_fntpgm_uint8_t fontpage_61_219_219[32] U8G_FONT_SECTION("fontpage_61_219_219") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdb,0xdb,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdb,0xdb,0x00,0x09,0x00,0x00, 0x00,0x05,0x09,0x09,0x07,0x00,0x00,0x20,0x40,0x10,0x08,0x70,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_221_221[32] U8G_FONT_SECTION("fontpage_61_221_221") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x09,0x00,0x00, 0x00,0x05,0x09,0x09,0x07,0x00,0x00,0x80,0x40,0x10,0x08,0x70,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_223_223[33] U8G_FONT_SECTION("fontpage_61_223_223") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x60,0x20,0x40,0x10,0x08,0x70,0x88,0x88,0x88, 0x70}; const u8g_fntpgm_uint8_t fontpage_61_225_225[32] U8G_FONT_SECTION("fontpage_61_225_225") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x09,0x00,0x00, 0x00,0x05,0x09,0x09,0x07,0x00,0x00,0x50,0xa0,0x10,0x08,0x70,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_227_227[32] U8G_FONT_SECTION("fontpage_61_227_227") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe3,0xe3,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe3,0xe3,0x00,0x07,0xfe,0x00, 0x00,0x05,0x09,0x09,0x00,0x00,0xfe,0x10,0x08,0x70,0x88,0x88,0x88,0x70,0x00,0x20 }; const u8g_fntpgm_uint8_t fontpage_61_229_229[30] U8G_FONT_SECTION("fontpage_61_229_229") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x05,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x05,0xfe,0x00, 0x00,0x05,0x07,0x07,0x07,0x00,0xfe,0x88,0x88,0x88,0x88,0x70,0x00,0x20}; const u8g_fntpgm_uint8_t fontpage_61_231_231[33] U8G_FONT_SECTION("fontpage_61_231_231") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0x00,0x00, 0x00,0x05,0x0a,0x0a,0x07,0x00,0x00,0x30,0x10,0x20,0x00,0x00,0x88,0x88,0x88,0x88, 0x70}; const u8g_fntpgm_uint8_t fontpage_61_233_233[32] U8G_FONT_SECTION("fontpage_61_233_233") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe9,0xe9,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe9,0xe9,0x00,0x09,0x00,0x00, 0x00,0x06,0x09,0x09,0x07,0x00,0x00,0x10,0x20,0x0c,0x04,0x88,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_235_235[32] U8G_FONT_SECTION("fontpage_61_235_235") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xeb,0xeb,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xeb,0xeb,0x00,0x09,0x00,0x00, 0x00,0x06,0x09,0x09,0x07,0x00,0x00,0x40,0x20,0x0c,0x04,0x88,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_237_237[33] U8G_FONT_SECTION("fontpage_61_237_237") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0x00,0x00, 0x00,0x06,0x0a,0x0a,0x07,0x00,0x00,0x30,0x10,0x20,0x0c,0x04,0x88,0x88,0x88,0x88, 0x70}; const u8g_fntpgm_uint8_t fontpage_61_239_239[32] U8G_FONT_SECTION("fontpage_61_239_239") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x09,0x00,0x00, 0x00,0x06,0x09,0x09,0x07,0x00,0x00,0x28,0x50,0x0c,0x04,0x88,0x88,0x88,0x88,0x70 }; const u8g_fntpgm_uint8_t fontpage_61_241_241[32] U8G_FONT_SECTION("fontpage_61_241_241") = { - 0x00,0x0c,0x0d,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x07,0xfe,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x07,0xfe,0x00, 0x00,0x06,0x09,0x09,0x07,0x00,0xfe,0x0c,0x04,0x88,0x88,0x88,0x88,0x70,0x00,0x20 }; @@ -203,7 +199,6 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(61, 179, 179, fontpage_61_179_179), // 'ẳ' -- 'ẳ' FONTDATA_ITEM(61, 181, 181, fontpage_61_181_181), // 'ẵ' -- 'ẵ' FONTDATA_ITEM(61, 183, 183, fontpage_61_183_183), // 'ặ' -- 'ặ' - FONTDATA_ITEM(61, 187, 187, fontpage_61_187_187), // 'ẻ' -- 'ẻ' FONTDATA_ITEM(61, 191, 191, fontpage_61_191_191), // 'ế' -- 'ế' FONTDATA_ITEM(61, 193, 193, fontpage_61_193_193), // 'ề' -- 'ề' FONTDATA_ITEM(61, 195, 195, fontpage_61_195_195), // 'ể' -- 'ể' diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h index 87183cd5df..98d005ec62 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h @@ -5,1041 +5,1044 @@ */ #include -const u8g_fntpgm_uint8_t fontpage_64_157_157[26] U8G_FONT_SECTION("fontpage_64_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x07,0x00,0x00, - 0x00,0x05,0x03,0x03,0x06,0x00,0x04,0xd8,0x48,0x90}; const u8g_fntpgm_uint8_t fontpage_69_191_191[28] U8G_FONT_SECTION("fontpage_69_191_191") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x08,0x18,0x28,0x48,0xf8}; const u8g_fntpgm_uint8_t fontpage_156_128_128[27] U8G_FONT_SECTION("fontpage_156_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x06,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x06,0x00,0x00, 0x00,0x0b,0x02,0x04,0x0c,0x00,0x04,0x00,0x40,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_156_137_139[97] U8G_FONT_SECTION("fontpage_156_137_139") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x8b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x8b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0a,0x14,0x0c,0x00,0xff,0x7f,0xc0,0x00,0x00,0x00,0x00,0x00,0x00,0x3f, 0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xff,0xe0,0x0b,0x0b,0x16,0x0c,0x00, 0xff,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x07,0xc0,0x04,0x00,0x04,0x00,0x04, 0x00,0x04,0x00,0x04,0x00,0xff,0xe0,0x0b,0x0a,0x14,0x0c,0x00,0xff,0xff,0xe0,0x04, 0x00,0x04,0x00,0x06,0x00,0x05,0x00,0x04,0x80,0x04,0x80,0x04,0x00,0x04,0x00,0x04, 0x00}; +const u8g_fntpgm_uint8_t fontpage_156_141_141[45] U8G_FONT_SECTION("fontpage_156_141_141") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x02,0x00,0x02,0x00,0x04,0x00,0x0d, + 0x00,0x14,0x80,0x24,0x40,0x44,0x20,0x84,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_156_157_157[45] U8G_FONT_SECTION("fontpage_156_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x29,0x40,0x4a,0x40,0xf7, 0x80,0x10,0x80,0x21,0x00,0x42,0x00,0xf7,0xc0,0x00,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_156_170_170[45] U8G_FONT_SECTION("fontpage_156_170_170") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaa,0xaa,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaa,0xaa,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0x14,0x00,0x22,0x00,0x49, 0x00,0x88,0xc0,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_156_173_173[45] U8G_FONT_SECTION("fontpage_156_173_173") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0xff,0x80,0x88,0x80,0x88, 0x80,0x88,0x80,0xff,0x80,0x88,0x80,0x08,0x00,0x08,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_156_187_187[45] U8G_FONT_SECTION("fontpage_156_187_187") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x04, 0x00,0x04,0x00,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_156_203_203[45] U8G_FONT_SECTION("fontpage_156_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x04,0x00,0x7f,0xc0,0x00,0x80,0x01, 0x00,0x02,0x00,0x04,0x00,0x08,0x00,0x30,0x00,0x48,0x00,0x87,0xe0}; const u8g_fntpgm_uint8_t fontpage_157_134_134[45] U8G_FONT_SECTION("fontpage_157_134_134") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0xff,0x80,0x01,0x00,0x02,0x00,0x0c,0x00,0x08, 0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x28,0x00,0x10,0x00}; const u8g_fntpgm_uint8_t fontpage_157_142_142[45] U8G_FONT_SECTION("fontpage_157_142_142") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0xff, 0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x1c,0x00}; const u8g_fntpgm_uint8_t fontpage_157_174_174[45] U8G_FONT_SECTION("fontpage_157_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x11,0x00,0x1f,0x00,0x00, 0x00,0xff,0xe0,0x80,0x20,0x1f,0x00,0x11,0x00,0x21,0x20,0xc0,0xe0}; const u8g_fntpgm_uint8_t fontpage_157_206_206[45] U8G_FONT_SECTION("fontpage_157_206_206") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xce,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xce,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x11,0x00,0x11,0x00,0x11, 0x00,0x11,0x00,0x2a,0x80,0x2a,0x80,0x44,0x40,0x88,0x40,0x10,0x20}; const u8g_fntpgm_uint8_t fontpage_157_228_228[45] U8G_FONT_SECTION("fontpage_157_228_228") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x0a,0x00,0x11,0x00,0x24, 0x80,0xc2,0x60,0x3f,0x80,0x01,0x00,0x0a,0x00,0x04,0x00,0x02,0x00}; const u8g_fntpgm_uint8_t fontpage_157_253_253[45] U8G_FONT_SECTION("fontpage_157_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x80,0x12,0x80,0x22,0x40,0x24,0x40,0x68, 0x20,0xa7,0xc0,0x22,0x40,0x22,0x40,0x22,0x40,0x24,0x40,0x28,0xc0}; const u8g_fntpgm_uint8_t fontpage_158_145_145[45] U8G_FONT_SECTION("fontpage_158_145_145") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x21,0x00,0x3f,0xe0,0x61, 0x00,0xa3,0x80,0x23,0x80,0x25,0x40,0x29,0x20,0x31,0x00,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_158_205_206[73] U8G_FONT_SECTION("fontpage_158_205_206") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xce,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xce,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x11,0x00,0x20,0x00,0x2f,0xe0,0x60, 0x00,0xa4,0x40,0x22,0x40,0x22,0x80,0x20,0x80,0x21,0x00,0x2f,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x10,0xc0,0x1f,0x00,0x29,0x00,0x29,0x00,0x69,0x00,0xaf,0xe0,0x29, 0x00,0x29,0x20,0x2a,0xa0,0x2d,0x60,0x28,0xa0}; const u8g_fntpgm_uint8_t fontpage_158_220_220[45] U8G_FONT_SECTION("fontpage_158_220_220") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x14,0x00,0x14,0x00,0x27,0xe0,0x2a,0x00,0x72, 0x00,0xa3,0xc0,0x22,0x00,0x22,0x00,0x23,0xe0,0x22,0x00,0x22,0x00}; const u8g_fntpgm_uint8_t fontpage_159_155_155[45] U8G_FONT_SECTION("fontpage_159_155_155") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x14,0x80,0x14,0x80,0x24,0x80,0x2f,0xe0,0x64, 0x80,0xa4,0x80,0x3f,0xe0,0x20,0x00,0x24,0x80,0x28,0x40,0x30,0x20}; const u8g_fntpgm_uint8_t fontpage_159_221_221[45] U8G_FONT_SECTION("fontpage_159_221_221") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x17,0xc0,0x14,0x40,0x24,0x40,0x27,0xc0,0x61, 0x00,0xaf,0xe0,0x21,0x00,0x23,0x80,0x25,0x40,0x29,0x20,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_159_225_225[45] U8G_FONT_SECTION("fontpage_159_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x11,0x00,0x2f,0xe0,0x20,0x00,0x67, 0xc0,0xa0,0x00,0x27,0xc0,0x20,0x00,0x27,0xc0,0x24,0x40,0x27,0xc0}; const u8g_fntpgm_uint8_t fontpage_160_188_188[45] U8G_FONT_SECTION("fontpage_160_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x1f,0xe0,0x22,0x00,0x27,0xc0,0x64, 0x40,0xa7,0xc0,0x24,0x40,0x27,0x40,0x25,0xc0,0x24,0x40,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_160_207_207[45] U8G_FONT_SECTION("fontpage_160_207_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x28,0x20,0x2f,0xe0,0x68, 0x00,0xaf,0xe0,0x2a,0xa0,0x2f,0xe0,0x2a,0xa0,0x3a,0xa0,0x28,0x60}; const u8g_fntpgm_uint8_t fontpage_160_220_220[45] U8G_FONT_SECTION("fontpage_160_220_220") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x3f,0xe0,0x20,0x00,0x4f,0xc0,0x48, 0x40,0xdf,0xe0,0x50,0x20,0x4f,0xc0,0x41,0x00,0x41,0x00,0x47,0x00}; const u8g_fntpgm_uint8_t fontpage_161_168_168[45] U8G_FONT_SECTION("fontpage_161_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x61,0x20,0x57,0xc0,0x41,0x40,0x77,0xe0,0xd1, 0x00,0x53,0xc0,0x56,0x40,0x53,0xc0,0x5a,0x40,0x52,0x40,0x43,0xc0}; const u8g_fntpgm_uint8_t fontpage_162_197_197[45] U8G_FONT_SECTION("fontpage_162_197_197") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x04,0x00,0xff,0xc0,0x08,0x00,0x11,0x00,0x7f, 0x80,0x12,0x80,0x12,0x00,0x12,0x00,0x22,0x40,0x22,0x40,0xc1,0xc0}; const u8g_fntpgm_uint8_t fontpage_162_200_200[45] U8G_FONT_SECTION("fontpage_162_200_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x24,0x00,0x3f,0xc0,0x44,0x00,0x84, 0x00,0xff,0xe0,0x12,0x00,0x12,0x00,0x12,0x20,0x22,0x20,0xc1,0xe0}; const u8g_fntpgm_uint8_t fontpage_162_229_229[45] U8G_FONT_SECTION("fontpage_162_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x18,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x0a, 0x00,0x0a,0x00,0x11,0x00,0x11,0x00,0x20,0x80,0x40,0x40,0x80,0x20}; const u8g_fntpgm_uint8_t fontpage_162_232_232[45] U8G_FONT_SECTION("fontpage_162_232_232") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xdf, 0x60,0x04,0x00,0x04,0x00,0x1f,0x00,0x04,0x00,0x04,0x00,0x7f,0xc0}; const u8g_fntpgm_uint8_t fontpage_162_241_241[45] U8G_FONT_SECTION("fontpage_162_241_241") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x7f,0xc0,0x11,0x00,0x11, 0x00,0x11,0x00,0xff,0xe0,0x00,0x00,0x11,0x00,0x20,0x80,0x40,0x40}; const u8g_fntpgm_uint8_t fontpage_162_243_243[45] U8G_FONT_SECTION("fontpage_162_243_243") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x11,0x00,0x7f,0xc0,0x04,0x00,0x04, 0x00,0xff,0xc0,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60}; const u8g_fntpgm_uint8_t fontpage_162_247_247[45] U8G_FONT_SECTION("fontpage_162_247_247") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0x3f, 0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff,0xe0,0x11,0x00,0xe0,0xe0}; const u8g_fntpgm_uint8_t fontpage_163_183_183[45] U8G_FONT_SECTION("fontpage_163_183_183") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x82,0x00,0x42,0x00,0x05,0x00,0x28,0x80,0x32, 0x60,0x41,0x00,0x4f,0xc0,0x80,0x80,0x87,0x00,0x81,0x00,0x00,0x80}; const u8g_fntpgm_uint8_t fontpage_163_198_198[45] U8G_FONT_SECTION("fontpage_163_198_198") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc6,0xc6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc6,0xc6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x0a,0x00,0x89,0x00,0x4f,0xe0,0x59,0x00,0x09, 0x00,0x2f,0xc0,0x29,0x00,0xcf,0xc0,0x49,0x00,0x49,0x00,0x4f,0xe0}; const u8g_fntpgm_uint8_t fontpage_163_201_201[45] U8G_FONT_SECTION("fontpage_163_201_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x81,0x00,0x4f,0xe0,0x40,0x00,0x07,0xc0,0x24, 0x40,0x24,0x40,0x27,0xc0,0xc1,0x00,0x45,0x40,0x49,0x20,0x53,0x20}; const u8g_fntpgm_uint8_t fontpage_163_250_251[73] U8G_FONT_SECTION("fontpage_163_250_251") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x44,0x40,0x44,0x40,0x44,0x40,0x7f, 0xc0,0x04,0x00,0x84,0x20,0x84,0x20,0x84,0x20,0x84,0x20,0xff,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x7f,0xc0,0x04,0x00,0x04,0x00,0xff,0xe0,0x04, 0x00,0x44,0x40,0x44,0x40,0x44,0x40,0x7f,0xc0}; const u8g_fntpgm_uint8_t fontpage_164_134_134[45] U8G_FONT_SECTION("fontpage_164_134_134") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x20,0x80,0x20,0x80,0x40, 0x40,0xbf,0xa0,0x08,0x80,0x08,0x80,0x10,0x80,0x20,0x80,0xc3,0x00}; const u8g_fntpgm_uint8_t fontpage_164_155_155[45] U8G_FONT_SECTION("fontpage_164_155_155") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x20,0x18,0x20,0x24,0xa0,0x42,0xa0,0xbc, 0xa0,0x24,0xa0,0x24,0xa0,0x38,0xa0,0x22,0x20,0x22,0x20,0x1e,0x60}; const u8g_fntpgm_uint8_t fontpage_164_157_157[45] U8G_FONT_SECTION("fontpage_164_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0x27,0xe0,0xf9,0x20,0x11,0x20,0x21, 0x20,0x69,0x20,0xb1,0x20,0x29,0x20,0x22,0x20,0x24,0x20,0x28,0xc0}; const u8g_fntpgm_uint8_t fontpage_164_176_176[45] U8G_FONT_SECTION("fontpage_164_176_176") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfe,0x20,0x10,0x20,0x20,0xa0,0x44,0xa0,0xfe, 0xa0,0x10,0xa0,0x7c,0xa0,0x10,0xa0,0x10,0x20,0x1e,0x20,0xe0,0xe0}; const u8g_fntpgm_uint8_t fontpage_164_182_183[73] U8G_FONT_SECTION("fontpage_164_182_183") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x20,0x50,0xa0,0x7e,0xa0,0x90,0xa0,0xfe, 0xa0,0x10,0xa0,0x7e,0xa0,0x52,0xa0,0x52,0x20,0x56,0x20,0x10,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x7e,0x20,0x42,0x20,0x7e,0xa0,0x48,0xa0,0x48,0xa0,0x7e,0xa0,0x6a, 0xa0,0xaa,0xa0,0xaa,0xa0,0x2e,0x20,0x08,0xe0}; const u8g_fntpgm_uint8_t fontpage_165_155_155[45] U8G_FONT_SECTION("fontpage_165_155_155") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0x08,0x00,0xff,0x80,0x08, 0x80,0x08,0x80,0x10,0x80,0x10,0x80,0x20,0x80,0x40,0x80,0x87,0x00}; const u8g_fntpgm_uint8_t fontpage_165_160_160[45] U8G_FONT_SECTION("fontpage_165_160_160") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x20,0x00,0xfd,0xe0,0x25,0x20,0x25, 0x20,0x25,0x20,0x25,0x20,0x25,0x20,0x45,0x20,0x55,0xe0,0x89,0x20}; const u8g_fntpgm_uint8_t fontpage_165_168_168[45] U8G_FONT_SECTION("fontpage_165_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0x79,0x00,0x01,0x00,0x03,0xe0,0xfd, 0x20,0x21,0x20,0x21,0x20,0x49,0x20,0xfa,0x20,0x0a,0x20,0x04,0xc0}; const u8g_fntpgm_uint8_t fontpage_166_150_150[45] U8G_FONT_SECTION("fontpage_166_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x12,0x00,0x22,0x40,0x22,0x80,0x63, 0x00,0xa2,0x00,0x26,0x00,0x2a,0x00,0x22,0x20,0x22,0x20,0x21,0xe0}; const u8g_fntpgm_uint8_t fontpage_166_202_202[45] U8G_FONT_SECTION("fontpage_166_202_202") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x44,0x40,0x24,0x80,0x15,0x00,0x7f, 0xc0,0x04,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_166_207_207[45] U8G_FONT_SECTION("fontpage_166_207_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x42,0x00,0x4f,0x80,0xe2,0x80,0x42, 0x80,0x4a,0xc0,0x52,0xa0,0x44,0x80,0x44,0x80,0x4a,0x80,0x51,0x00}; const u8g_fntpgm_uint8_t fontpage_166_213_213[45] U8G_FONT_SECTION("fontpage_166_213_213") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x0a,0x00,0x7f,0xc0,0x44,0x40,0x7f, 0xc0,0x44,0x40,0x7f,0xc0,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_166_225_225[45] U8G_FONT_SECTION("fontpage_166_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x0f,0x80,0x08,0x00,0x08,0x00,0xff, 0xe0,0x08,0x00,0x0a,0x00,0x09,0x00,0x08,0x80,0x08,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_166_240_240[45] U8G_FONT_SECTION("fontpage_166_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x10,0x00,0xe7,0xc0,0x84,0x40,0x84,0x40,0xf4, 0x40,0x84,0x40,0x84,0x40,0x94,0x40,0xe5,0x80,0x84,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_166_248_248[45] U8G_FONT_SECTION("fontpage_166_248_248") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0x7d,0xe0,0x91,0x20,0x11,0x20,0xff, 0x20,0x11,0x20,0x5d,0x20,0x51,0x20,0x51,0xa0,0x5d,0x40,0xe1,0x00}; const u8g_fntpgm_uint8_t fontpage_167_159_159[45] U8G_FONT_SECTION("fontpage_167_159_159") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0xe0,0x22,0x00,0x2f,0xc0,0x28,0x40,0x2f, 0xc0,0x28,0x40,0x2f,0xc0,0x22,0x00,0x2a,0x80,0x52,0x60,0xa6,0x20}; const u8g_fntpgm_uint8_t fontpage_167_204_204[43] U8G_FONT_SECTION("fontpage_167_204_204") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x09,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x09,0xff,0x00, 0x00,0x0b,0x0a,0x14,0x0c,0x00,0xff,0xff,0xe0,0x0a,0x40,0x4a,0x40,0x2a,0x40,0x11, 0x40,0x11,0x40,0x28,0x80,0x45,0x80,0x82,0x40,0x04,0x20}; const u8g_fntpgm_uint8_t fontpage_167_214_214[45] U8G_FONT_SECTION("fontpage_167_214_214") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfc,0x00,0x4b,0xe0,0x4a,0x20,0x7a,0x20,0x49, 0x40,0x79,0x40,0x48,0x80,0x4c,0x80,0xf9,0x40,0x0a,0x40,0x0c,0x20}; const u8g_fntpgm_uint8_t fontpage_167_216_216[45] U8G_FONT_SECTION("fontpage_167_216_216") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0xff,0xc0,0x12,0x00,0x52,0x80,0x92, 0x40,0x00,0x00,0x7f,0x80,0x12,0x00,0x0c,0x00,0x12,0x00,0xe1,0xc0}; const u8g_fntpgm_uint8_t fontpage_167_240_240[45] U8G_FONT_SECTION("fontpage_167_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x10,0x00,0x22,0x00,0x41,0x00,0xff, 0x80,0x00,0x80,0x7f,0x00,0x41,0x00,0x41,0x00,0x41,0x00,0x7f,0x00}; const u8g_fntpgm_uint8_t fontpage_168_136_136[45] U8G_FONT_SECTION("fontpage_168_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xdf, 0x60,0x00,0x00,0x3f,0x80,0x20,0x80,0x20,0x80,0x3f,0x80,0x20,0x80}; const u8g_fntpgm_uint8_t fontpage_168_142_142[45] U8G_FONT_SECTION("fontpage_168_142_142") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0xc0,0x3e,0x00,0x20,0x00,0x3f,0xe0,0x20, 0x00,0x20,0x00,0x2f,0xc0,0x28,0x40,0x48,0x40,0x4f,0xc0,0x88,0x40}; const u8g_fntpgm_uint8_t fontpage_168_175_175[45] U8G_FONT_SECTION("fontpage_168_175_175") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x3f,0xc0,0x20,0x40,0x20,0x40,0x3f, 0xc0,0x20,0x00,0x3f,0xc0,0x30,0x40,0x50,0x40,0x5f,0xc0,0x90,0x40}; const u8g_fntpgm_uint8_t fontpage_168_253_253[45] U8G_FONT_SECTION("fontpage_168_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x0a,0x00,0x11,0x00,0xee,0xe0,0x00, 0x00,0x7b,0xc0,0x4a,0x40,0x4a,0x40,0x7a,0x40,0x4a,0xc0,0x02,0x00}; const u8g_fntpgm_uint8_t fontpage_169_140_140[45] U8G_FONT_SECTION("fontpage_169_140_140") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x0c,0x00,0x70,0x00,0x11,0xe0,0xfd,0x20,0x11, 0x20,0x39,0x20,0x35,0x20,0x55,0x20,0x91,0x20,0x11,0xe0,0x10,0x00}; const u8g_fntpgm_uint8_t fontpage_171_183_183[45] U8G_FONT_SECTION("fontpage_171_183_183") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0xef,0xe0,0xa5,0x40,0xaf,0xe0,0xa4, 0x40,0xaf,0xe0,0xe8,0x20,0xa9,0x20,0x09,0x20,0x02,0x80,0x0c,0x60}; const u8g_fntpgm_uint8_t fontpage_172_180_180[45] U8G_FONT_SECTION("fontpage_172_180_180") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb4,0xb4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb4,0xb4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0xa0,0xeb,0xc0,0xaa,0xa0,0xbf,0xe0,0xa4, 0x80,0xaf,0xe0,0xf9,0x20,0x0f,0xe0,0x09,0x20,0x0f,0xe0,0x11,0x20}; -const u8g_fntpgm_uint8_t fontpage_172_244_244[45] U8G_FONT_SECTION("fontpage_172_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0xef,0xe0,0xa5,0x40,0xaf,0xe0,0xa4, - 0x40,0xa7,0xc0,0xe4,0x40,0x07,0xc0,0x04,0x40,0x07,0xc0,0x0c,0x60}; const u8g_fntpgm_uint8_t fontpage_173_222_222[45] U8G_FONT_SECTION("fontpage_173_222_222") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x80,0x40,0x80,0x40,0x9e,0x40,0x92, 0x40,0x92,0x40,0x9e,0x40,0x92,0x40,0x80,0x40,0xff,0xc0,0x80,0x40}; const u8g_fntpgm_uint8_t fontpage_173_224_224[45] U8G_FONT_SECTION("fontpage_173_224_224") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x84,0x20,0x84,0x20,0xbf,0xa0,0x84, 0x20,0x84,0x20,0x8a,0x20,0x91,0x20,0xa0,0xa0,0x80,0x20,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_173_254_254[45] U8G_FONT_SECTION("fontpage_173_254_254") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfe,0xfe,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfe,0xfe,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x90,0x40,0x9f,0x40,0xb2,0x40,0xcc, 0x40,0x92,0x40,0xe9,0xc0,0x84,0x40,0x88,0x40,0x84,0x40,0xff,0xc0}; const u8g_fntpgm_uint8_t fontpage_174_168_168[45] U8G_FONT_SECTION("fontpage_174_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0xff,0xc0,0x10,0x00,0x22, 0x00,0x62,0x00,0xaf,0x80,0x22,0x00,0x22,0x00,0x22,0x00,0x3f,0xc0}; const u8g_fntpgm_uint8_t fontpage_174_215_215[45] U8G_FONT_SECTION("fontpage_174_215_215") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd7,0xd7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd7,0xd7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x27,0xc0,0xf9,0x40,0x21, 0x40,0x21,0x40,0x2f,0xe0,0x31,0x00,0xc2,0x80,0x04,0x40,0x18,0x20}; const u8g_fntpgm_uint8_t fontpage_175_139_139[45] U8G_FONT_SECTION("fontpage_175_139_139") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7e,0x40,0x29,0x40,0x29,0x40,0xff,0x40,0x29, 0x40,0x28,0x40,0x4c,0xc0,0x04,0x00,0x3f,0x80,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_175_171_171[45] U8G_FONT_SECTION("fontpage_175_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0xff,0x80,0x22,0x80,0x36,0xa0,0xe3, 0xa0,0x2c,0xe0,0x64,0x00,0x04,0x00,0x3f,0xc0,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_176_235_235[45] U8G_FONT_SECTION("fontpage_176_235_235") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xeb,0xeb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xeb,0xeb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x21,0x00,0xf7,0xc0,0x24, 0x40,0x27,0x40,0x25,0xc0,0x34,0x40,0xef,0xe0,0x02,0x80,0x0c,0x60}; const u8g_fntpgm_uint8_t fontpage_177_243_243[45] U8G_FONT_SECTION("fontpage_177_243_243") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x04,0x00,0x3f,0xc0,0x00, 0x00,0xff,0xe0,0x80,0x20,0x1f,0x00,0x11,0x20,0x21,0x20,0xc0,0xe0}; const u8g_fntpgm_uint8_t fontpage_178_135_135[45] U8G_FONT_SECTION("fontpage_178_135_135") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x00,0x1f,0x80,0x31,0x00,0x4e,0x00,0x0b, 0x00,0x30,0xe0,0xff,0x80,0x24,0x80,0x3f,0x80,0x24,0x80,0x3f,0x80}; const u8g_fntpgm_uint8_t fontpage_178_141_141[45] U8G_FONT_SECTION("fontpage_178_141_141") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x3f,0xe0,0x60,0x80,0xbf,0x80,0x20, 0x80,0x3f,0x80,0x10,0x00,0x3f,0x80,0xc9,0x00,0x06,0x00,0xf9,0xe0}; const u8g_fntpgm_uint8_t fontpage_178_150_150[45] U8G_FONT_SECTION("fontpage_178_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x3d,0x00,0x25,0x00,0x45, 0x80,0xa5,0x40,0x19,0x20,0x09,0x00,0x11,0x00,0x21,0x00,0x41,0x00}; const u8g_fntpgm_uint8_t fontpage_178_154_154[45] U8G_FONT_SECTION("fontpage_178_154_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x1f,0x00,0x21,0x00,0x52,0x00,0x0c, 0x00,0x34,0x00,0xcf,0x80,0x10,0x80,0x69,0x00,0x06,0x00,0xf8,0x00}; const u8g_fntpgm_uint8_t fontpage_178_167_167[45] U8G_FONT_SECTION("fontpage_178_167_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0,0x04, 0x00,0x04,0x00,0x0a,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60}; const u8g_fntpgm_uint8_t fontpage_178_169_170[73] U8G_FONT_SECTION("fontpage_178_169_170") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xaa,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xaa,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0xff, 0xe0,0x04,0x00,0x0a,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x0a,0x00,0x0a, 0x00,0x11,0x00,0x19,0x00,0x24,0x80,0xc4,0x60}; const u8g_fntpgm_uint8_t fontpage_178_177_177[45] U8G_FONT_SECTION("fontpage_178_177_177") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x00,0x24,0x00,0x3f,0xc0,0x44,0x00,0x04, 0x00,0xff,0xe0,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60}; const u8g_fntpgm_uint8_t fontpage_179_203_203[45] U8G_FONT_SECTION("fontpage_179_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0xfa,0x40,0x2a,0x20,0x2f, 0xe0,0x48,0x00,0x53,0xe0,0x32,0x20,0x2a,0x20,0x4b,0xe0,0x82,0x20}; const u8g_fntpgm_uint8_t fontpage_182_208_208[45] U8G_FONT_SECTION("fontpage_182_208_208") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x01,0x00,0x02,0x00,0x04,0x00,0x04, 0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x14,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_182_216_216[45] U8G_FONT_SECTION("fontpage_182_216_216") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0xff,0xe0,0x10,0x00,0x2f,0xc0,0x20, 0x80,0x61,0x00,0xbf,0xe0,0x21,0x00,0x21,0x00,0x21,0x00,0x27,0x00}; const u8g_fntpgm_uint8_t fontpage_183_137_137[45] U8G_FONT_SECTION("fontpage_183_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x88,0x40,0x08, 0x00,0xff,0xe0,0x11,0x00,0x31,0x00,0x0e,0x00,0x09,0x80,0x70,0x60}; const u8g_fntpgm_uint8_t fontpage_183_140_140[45] U8G_FONT_SECTION("fontpage_183_140_140") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x9f,0x40,0x00, 0x00,0x7f,0xe0,0x0a,0x00,0x12,0x00,0x12,0x20,0x22,0x20,0x41,0xe0}; const u8g_fntpgm_uint8_t fontpage_183_154_154[45] U8G_FONT_SECTION("fontpage_183_154_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x80,0x40,0x3f, 0xc0,0x04,0x00,0x24,0x00,0x27,0x80,0x24,0x00,0x54,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_183_162_162[45] U8G_FONT_SECTION("fontpage_183_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0xff,0xc0,0x90,0x40,0x3f,0x00,0x52, 0x00,0x8c,0x00,0x33,0x00,0xff,0xc0,0x21,0x00,0x21,0x00,0x3f,0x00}; const u8g_fntpgm_uint8_t fontpage_183_185_185[45] U8G_FONT_SECTION("fontpage_183_185_185") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x91,0x20,0x24,0x80,0x4a, 0x40,0x11,0x00,0x20,0x80,0xdf,0x60,0x11,0x00,0x11,0x00,0x1f,0x00}; const u8g_fntpgm_uint8_t fontpage_183_249_249[45] U8G_FONT_SECTION("fontpage_183_249_249") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x00,0x80,0xf0,0x80,0x1f,0xe0,0x90,0x80,0x50, 0x80,0x24,0x80,0x22,0x80,0x50,0x80,0x50,0x80,0x82,0x80,0x01,0x00}; const u8g_fntpgm_uint8_t fontpage_184_143_143[45] U8G_FONT_SECTION("fontpage_184_143_143") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0x24,0x80,0x24, 0x40,0x44,0x40,0x44,0x20,0x84,0x20,0x04,0x00,0x14,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_184_177_177[45] U8G_FONT_SECTION("fontpage_184_177_177") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xfd,0x40,0x01,0x20,0x7f,0xe0,0x4a, 0x80,0x7a,0x80,0x12,0x80,0x5a,0xa0,0x56,0xa0,0x92,0xa0,0x34,0x60}; const u8g_fntpgm_uint8_t fontpage_184_207_207[45] U8G_FONT_SECTION("fontpage_184_207_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0xe0,0x20,0x20,0x3f,0xe0,0x28,0x40,0x24, 0x80,0x3f,0xe0,0x24,0x80,0x3f,0xe0,0x24,0x80,0x48,0x80,0x90,0x80}; const u8g_fntpgm_uint8_t fontpage_187_229_229[41] U8G_FONT_SECTION("fontpage_187_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x09,0x00,0x00, 0x00,0x0b,0x09,0x12,0x0c,0x00,0x00,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0x04, 0x00,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_187_242_242[43] U8G_FONT_SECTION("fontpage_187_242_242") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x09,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x09,0xff,0x00, 0x00,0x0a,0x0a,0x14,0x0c,0x01,0xff,0xff,0x00,0x01,0x00,0x01,0x00,0x81,0x00,0xff, 0x00,0x80,0x00,0x80,0x40,0x80,0x40,0x80,0x40,0x7f,0xc0}; const u8g_fntpgm_uint8_t fontpage_188_243_243[45] U8G_FONT_SECTION("fontpage_188_243_243") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0x24,0x80,0x15,0x00,0x04, 0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_188_246_246[45] U8G_FONT_SECTION("fontpage_188_246_246") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf6,0xf6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf6,0xf6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x11,0x00,0x7f,0xc0,0x11,0x00,0x11, 0x00,0x11,0x00,0xff,0xe0,0x11,0x00,0x11,0x00,0x21,0x00,0x41,0x00}; const u8g_fntpgm_uint8_t fontpage_189_138_138[45] U8G_FONT_SECTION("fontpage_189_138_138") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0x7f,0xe0,0x42,0x00,0x42,0x00,0x7f, 0xe0,0x42,0x00,0x47,0x00,0x4a,0x80,0x52,0x40,0xa2,0x20,0x82,0x00}; const u8g_fntpgm_uint8_t fontpage_189_148_148[45] U8G_FONT_SECTION("fontpage_189_148_148") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x94,0x94,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x94,0x94,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x02,0x00,0x7f,0xe0,0x40,0x00,0x44, 0x40,0x52,0x40,0x4a,0x40,0x48,0x80,0x40,0x80,0x81,0x00,0x9f,0xe0}; const u8g_fntpgm_uint8_t fontpage_189_159_159[45] U8G_FONT_SECTION("fontpage_189_159_159") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0x3f,0xe0,0x2a,0x80,0x2a,0x40,0x3f, 0xe0,0x24,0x00,0x27,0xc0,0x2a,0x40,0x31,0x80,0x42,0x40,0x8c,0x20}; const u8g_fntpgm_uint8_t fontpage_189_166_166[45] U8G_FONT_SECTION("fontpage_189_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x49,0x00,0x7f,0xc0,0x49, 0x00,0x4f,0x00,0x40,0x00,0x5f,0x80,0x49,0x00,0x86,0x00,0xb9,0xc0}; const u8g_fntpgm_uint8_t fontpage_190_128_128[45] U8G_FONT_SECTION("fontpage_190_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x11,0x00,0x11,0x00,0x11,0x00,0x11, 0x00,0xff,0xe0,0x11,0x00,0x21,0x00,0x21,0x00,0x41,0x00,0x81,0x00}; const u8g_fntpgm_uint8_t fontpage_190_210_210[45] U8G_FONT_SECTION("fontpage_190_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x10,0x00,0x17,0xc0,0x90,0x40,0x90,0x40,0x90, 0x40,0x97,0xc0,0x90,0x40,0x90,0x40,0x20,0x40,0x4f,0xc0,0x80,0x40}; const u8g_fntpgm_uint8_t fontpage_191_132_133[73] U8G_FONT_SECTION("fontpage_191_132_133") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x85,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x85,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x17,0xc0,0x20,0x80,0x49,0x00,0x92,0x80,0x24, 0x40,0x68,0x20,0xa7,0xc0,0x21,0x00,0x21,0x00,0x21,0x00,0x2f,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x11,0x00,0x21,0x00,0x47,0xc0,0x91,0x00,0x1f,0xe0,0x20,0x80,0x6f, 0xe0,0xa4,0x80,0x22,0x80,0x20,0x80,0x21,0x80}; const u8g_fntpgm_uint8_t fontpage_191_174_174[45] U8G_FONT_SECTION("fontpage_191_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2a,0x80,0x6a,0x80,0xbe,0x80,0x01,0xe0,0x5d, 0x40,0xc3,0x40,0x5d,0x40,0x54,0x80,0x56,0x80,0x55,0x40,0x62,0x20}; const u8g_fntpgm_uint8_t fontpage_191_195_195[45] U8G_FONT_SECTION("fontpage_191_195_195") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x02,0x00,0x12,0x00,0x12,0x00,0x10, 0x40,0x50,0x20,0x50,0x20,0x50,0xa0,0x90,0x80,0x10,0x80,0x0f,0x80}; const u8g_fntpgm_uint8_t fontpage_192_167_167[45] U8G_FONT_SECTION("fontpage_192_167_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x25,0x00,0xb5,0x00,0xaf,0xe0,0xa9, 0x00,0xb1,0x00,0x27,0xc0,0x21,0x00,0x21,0x00,0x21,0x00,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_192_187_187[45] U8G_FONT_SECTION("fontpage_192_187_187") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x0a,0x00,0x3f,0x80,0x20,0x80,0x20, 0x80,0x3f,0x80,0x20,0x80,0x04,0x40,0x52,0xa0,0x50,0xa0,0x8f,0x80}; const u8g_fntpgm_uint8_t fontpage_192_226_226[45] U8G_FONT_SECTION("fontpage_192_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x2f,0xe0,0xb2,0x00,0xaa,0x80,0xa4, 0x80,0xa5,0xa0,0x2a,0xc0,0x30,0x80,0x21,0x40,0x22,0x40,0x24,0x20}; const u8g_fntpgm_uint8_t fontpage_192_239_239[45] U8G_FONT_SECTION("fontpage_192_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20, 0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x54,0x40,0x52,0xa0,0x8f,0x80}; const u8g_fntpgm_uint8_t fontpage_196_144_144[45] U8G_FONT_SECTION("fontpage_196_144_144") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x80,0x02,0x40,0x7f,0xe0,0x42,0x00,0x42, 0x00,0x7a,0x40,0x4a,0x40,0x4a,0x80,0x49,0x20,0x52,0xa0,0x84,0x60}; const u8g_fntpgm_uint8_t fontpage_196_183_183[45] U8G_FONT_SECTION("fontpage_196_183_183") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x02,0x00,0x3f,0xc0,0x20,0x40,0x20, 0x40,0x3f,0xc0,0x20,0x00,0x20,0x00,0x20,0x00,0x40,0x00,0x80,0x00}; const u8g_fntpgm_uint8_t fontpage_196_192_192[45] U8G_FONT_SECTION("fontpage_196_192_192") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x18,0x60,0x63,0x80,0x42,0x00,0x7a,0x00,0x4b, 0xe0,0x4a,0x40,0x7a,0x40,0x42,0x40,0x42,0x40,0x44,0x40,0x88,0x40}; const u8g_fntpgm_uint8_t fontpage_196_199_199[45] U8G_FONT_SECTION("fontpage_196_199_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x7f,0xe0,0x40, 0x00,0x7d,0xe0,0x44,0x20,0x54,0xa0,0x4c,0x60,0x54,0xa0,0xa9,0x60}; const u8g_fntpgm_uint8_t fontpage_196_203_203[45] U8G_FONT_SECTION("fontpage_196_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x03,0xc0,0x7c,0x00,0x04,0x00,0x7f,0xc0,0x04, 0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x0c,0x00}; const u8g_fntpgm_uint8_t fontpage_196_211_211[45] U8G_FONT_SECTION("fontpage_196_211_211") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd3,0xd3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd3,0xd3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xe0,0xf8,0x80,0x20,0x80,0x28, 0x80,0x30,0x80,0x60,0x80,0xa0,0x80,0x20,0x80,0x20,0x80,0xe3,0x80}; const u8g_fntpgm_uint8_t fontpage_196_231_231[45] U8G_FONT_SECTION("fontpage_196_231_231") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x22,0x00,0xff,0x80,0x22,0x80,0x2a, 0x80,0x36,0x80,0x62,0x80,0xa7,0xa0,0x24,0xa0,0xa8,0xa0,0x50,0x60}; const u8g_fntpgm_uint8_t fontpage_196_249_249[45] U8G_FONT_SECTION("fontpage_196_249_249") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x80,0x24,0x80,0xfc,0x80,0x24,0xa0,0x2f, 0xc0,0x34,0x80,0x64,0x80,0xa4,0x80,0x25,0xa0,0x26,0xa0,0xe4,0x60}; const u8g_fntpgm_uint8_t fontpage_197_150_150[45] U8G_FONT_SECTION("fontpage_197_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x40,0x22,0x40,0xf9,0x40,0x20,0x40,0x2a, 0x40,0x31,0x40,0x60,0xe0,0xaf,0x40,0x20,0x40,0x20,0x40,0xe0,0x40}; const u8g_fntpgm_uint8_t fontpage_197_189_189[45] U8G_FONT_SECTION("fontpage_197_189_189") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x20,0x80,0xf8,0x80,0x27,0xe0,0x2c, 0xa0,0x34,0xa0,0x67,0xe0,0xa4,0xa0,0x24,0xa0,0x27,0xe0,0xe4,0x20}; const u8g_fntpgm_uint8_t fontpage_197_212_212[45] U8G_FONT_SECTION("fontpage_197_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x80,0x22,0x40,0xff,0xe0,0x22,0x00,0x2b, 0xc0,0x32,0x40,0x65,0x40,0xa4,0x80,0x28,0x80,0x29,0x40,0xe6,0x20}; const u8g_fntpgm_uint8_t fontpage_197_233_233[45] U8G_FONT_SECTION("fontpage_197_233_233") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe9,0xe9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe9,0xe9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0xe0,0x22,0x40,0xf9,0x80,0x22,0x40,0x2c, 0x20,0x31,0x00,0x67,0xc0,0xa1,0x00,0x2f,0xe0,0x21,0x00,0xe1,0x00}; const u8g_fntpgm_uint8_t fontpage_198_137_137[45] U8G_FONT_SECTION("fontpage_198_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x20,0x80,0xff,0xe0,0x25,0x20,0x29, 0x00,0x37,0xe0,0x62,0x40,0xa6,0x40,0x21,0x80,0x22,0x80,0xec,0x60}; const u8g_fntpgm_uint8_t fontpage_198_161_161[45] U8G_FONT_SECTION("fontpage_198_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x25,0x20,0xfb,0x40,0x21,0x00,0x2f, 0xe0,0x30,0x20,0x60,0x20,0xa7,0xe0,0x20,0x20,0x20,0x20,0xef,0xe0}; const u8g_fntpgm_uint8_t fontpage_198_164_164[45] U8G_FONT_SECTION("fontpage_198_164_164") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xe0,0xfa,0x40,0x21,0x80,0x2e, 0x60,0x30,0x00,0x62,0x40,0xa2,0x40,0x22,0x40,0x24,0x40,0xe8,0x40}; const u8g_fntpgm_uint8_t fontpage_198_226_226[45] U8G_FONT_SECTION("fontpage_198_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xc0,0xfc,0x80,0x27,0xc0,0x2d, 0x40,0x35,0x40,0x6f,0xe0,0xa1,0x00,0x22,0x80,0x24,0x40,0xe8,0x20}; const u8g_fntpgm_uint8_t fontpage_199_137_137[45] U8G_FONT_SECTION("fontpage_199_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0xe0,0xf9,0x00,0x27,0xc0,0x2c, 0x40,0x37,0xc0,0x64,0x40,0xa7,0xc0,0x21,0x00,0x2f,0xe0,0xe1,0x00}; const u8g_fntpgm_uint8_t fontpage_199_162_162[45] U8G_FONT_SECTION("fontpage_199_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0xe0,0x28,0x20,0xf2,0x80,0x24,0x40,0x29, 0x20,0x31,0x00,0x6f,0xe0,0xa1,0x00,0x25,0x80,0x29,0x40,0xf1,0x20}; const u8g_fntpgm_uint8_t fontpage_199_167_167[45] U8G_FONT_SECTION("fontpage_199_167_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0xf8,0x20,0x22,0x80,0x24, 0x40,0x38,0x20,0x67,0xc0,0xa1,0x00,0x21,0x00,0x21,0x00,0xef,0xe0}; const u8g_fntpgm_uint8_t fontpage_199_210_210[45] U8G_FONT_SECTION("fontpage_199_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0xc0,0x27,0x00,0xf1,0x00,0x2f,0xe0,0x21, 0x00,0x35,0x60,0x69,0x20,0xad,0x60,0x29,0x20,0x29,0x20,0xef,0xe0}; const u8g_fntpgm_uint8_t fontpage_202_182_182[45] U8G_FONT_SECTION("fontpage_202_182_182") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x12,0x00,0x93,0xe0,0x94,0x40,0x9a, 0x40,0x92,0x40,0xb2,0x80,0xd1,0x00,0x91,0x80,0x12,0x40,0x14,0x20}; const u8g_fntpgm_uint8_t fontpage_202_190_190[45] U8G_FONT_SECTION("fontpage_202_190_190") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x11,0x00,0xfd,0xe0,0x22,0x40,0x25, 0x40,0x39,0x40,0x29,0x40,0x28,0x80,0x49,0x80,0x4a,0x40,0x94,0x20}; const u8g_fntpgm_uint8_t fontpage_202_240_240[45] U8G_FONT_SECTION("fontpage_202_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x95,0x00,0x59,0x00,0xfd,0xe0,0x33,0x40,0x59, 0x40,0x95,0x40,0xfd,0x40,0x29,0x40,0x68,0x80,0x11,0x40,0xee,0x20}; const u8g_fntpgm_uint8_t fontpage_202_244_244[45] U8G_FONT_SECTION("fontpage_202_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x55,0x40,0x7c,0x80,0x39, 0x40,0x56,0x20,0x7f,0xc0,0x04,0x00,0x27,0x80,0x24,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_203_153_153[45] U8G_FONT_SECTION("fontpage_203_153_153") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0xac,0x80,0x72,0x80,0x20,0x80,0xfc, 0x80,0x22,0x80,0x30,0xe0,0x6f,0x80,0xa0,0x80,0x20,0x80,0x20,0x80}; const u8g_fntpgm_uint8_t fontpage_203_156_156[45] U8G_FONT_SECTION("fontpage_203_156_156") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0x9c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0x9c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x40,0x29,0x40,0x44,0xc0,0xb8,0x40,0x12, 0x40,0x7d,0x40,0x10,0x60,0x55,0xc0,0x52,0x40,0x92,0x40,0x30,0x40}; const u8g_fntpgm_uint8_t fontpage_203_176_176[45] U8G_FONT_SECTION("fontpage_203_176_176") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x60,0xfd,0x80,0x45,0x00,0x29,0x00,0xfd, 0xe0,0x11,0x40,0xfd,0x40,0x11,0x40,0x55,0x40,0x92,0x40,0x34,0x40}; const u8g_fntpgm_uint8_t fontpage_203_224_224[45] U8G_FONT_SECTION("fontpage_203_224_224") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0xff, 0xe0,0x0a,0x00,0x0a,0x00,0x12,0x00,0x12,0x20,0x22,0x20,0xc1,0xe0}; const u8g_fntpgm_uint8_t fontpage_203_246_246[45] U8G_FONT_SECTION("fontpage_203_246_246") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf6,0xf6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf6,0xf6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x00,0x80,0xf0,0x80,0x9f,0xe0,0x90,0x80,0x94, 0x80,0xf2,0x80,0x92,0x80,0x90,0x80,0x90,0x80,0xf0,0x80,0x03,0x80}; const u8g_fntpgm_uint8_t fontpage_204_142_142[45] U8G_FONT_SECTION("fontpage_204_142_142") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x03,0xe0,0xf2,0x20,0x92,0x20,0x93,0xe0,0xf2, 0x20,0x92,0x20,0x93,0xe0,0xf2,0x20,0x04,0x20,0x08,0xa0,0x30,0x40}; const u8g_fntpgm_uint8_t fontpage_205_130_130[45] U8G_FONT_SECTION("fontpage_205_130_130") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x82,0x82,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x82,0x82,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x40,0xfb,0x80,0x52,0x00,0xfb,0xe0,0x12, 0x80,0xf4,0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0x3f,0x80}; const u8g_fntpgm_uint8_t fontpage_205_171_171[45] U8G_FONT_SECTION("fontpage_205_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0xe0,0xff,0x00,0x55,0xe0,0x7d,0x40,0x55, 0x40,0xff,0xc0,0x10,0x40,0x1f,0xc0,0x10,0x40,0x1f,0xc0,0x10,0x40}; const u8g_fntpgm_uint8_t fontpage_205_244_244[45] U8G_FONT_SECTION("fontpage_205_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xe0,0x02,0x00,0x3f,0xc0,0x22,0x40,0x3f, 0xc0,0x22,0x40,0x3f,0xc0,0x0a,0x00,0x04,0x00,0x1b,0x00,0xe0,0xe0}; const u8g_fntpgm_uint8_t fontpage_206_128_128[45] U8G_FONT_SECTION("fontpage_206_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff, 0xe0,0x48,0x00,0x7f,0xc0,0x4a,0x40,0x79,0x80,0xc9,0x80,0x0e,0x60}; const u8g_fntpgm_uint8_t fontpage_206_137_137[45] U8G_FONT_SECTION("fontpage_206_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0xff,0xe0,0x10,0x00,0x1f,0x80,0x30, 0x80,0x5f,0x80,0x90,0x80,0x1f,0x80,0x10,0x80,0x10,0x80,0x11,0x80}; const u8g_fntpgm_uint8_t fontpage_206_186_186[45] U8G_FONT_SECTION("fontpage_206_186_186") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0x80,0x24,0x80,0xfc,0x80,0x24, 0x80,0x74,0x80,0x6c,0x80,0xa4,0x80,0xa4,0x80,0x28,0xa0,0x30,0xe0}; const u8g_fntpgm_uint8_t fontpage_206_192_192[45] U8G_FONT_SECTION("fontpage_206_192_192") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x19,0x00,0x06,0x00,0x19,0x00,0x64, 0xc0,0x04,0x00,0xff,0xe0,0x15,0x00,0x24,0x80,0xc4,0x60,0x0c,0x00}; const u8g_fntpgm_uint8_t fontpage_206_225_225[45] U8G_FONT_SECTION("fontpage_206_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x00,0x1f,0x80,0x29,0x00,0x46,0x00,0x0a, 0x00,0x35,0x80,0xc4,0x60,0x3f,0x80,0x15,0x00,0x24,0x80,0xdc,0x40}; const u8g_fntpgm_uint8_t fontpage_206_229_229[45] U8G_FONT_SECTION("fontpage_206_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xc0,0x24,0x80,0x15,0x00,0xff, 0xe0,0x04,0x00,0x0e,0x00,0x15,0x00,0x24,0x80,0xc4,0x60,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_206_255_255[45] U8G_FONT_SECTION("fontpage_206_255_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0xc0,0x27,0x00,0xfc,0x00,0x24,0x00,0x27, 0xc0,0x74,0x40,0x6e,0x40,0xa5,0x80,0x28,0x80,0x29,0x40,0x36,0x20}; const u8g_fntpgm_uint8_t fontpage_207_241_241[45] U8G_FONT_SECTION("fontpage_207_241_241") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x21,0x00,0xff,0xe0,0x21,0x00,0x71, 0x00,0x69,0x00,0xa7,0xc0,0xa1,0x00,0x21,0x00,0x21,0x00,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_208_161_161[45] U8G_FONT_SECTION("fontpage_208_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x21,0x00,0x2f,0xe0,0xf0,0x00,0x22, 0x80,0x74,0x40,0x6a,0xa0,0xa2,0x80,0x21,0x00,0x22,0x80,0x2c,0x60}; const u8g_fntpgm_uint8_t fontpage_208_188_188[45] U8G_FONT_SECTION("fontpage_208_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xc0,0xf4,0x40,0x2a,0x80,0x21, 0x00,0x72,0x80,0x6c,0x60,0xa7,0xc0,0x24,0x40,0x24,0x40,0x27,0xc0}; const u8g_fntpgm_uint8_t fontpage_209_192_192[45] U8G_FONT_SECTION("fontpage_209_192_192") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x22,0x80,0xfc,0x40,0x28,0x20,0x27, 0xc0,0x70,0x00,0x69,0x20,0xa4,0xa0,0x22,0x40,0x22,0x80,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_211_253_253[45] U8G_FONT_SECTION("fontpage_211_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x80,0x2f,0xe0,0xfa,0xa0,0x2f,0xe0,0x2a, 0xa0,0x3f,0xe0,0x64,0x40,0xa7,0xc0,0x24,0x40,0x27,0xc0,0x24,0x40}; const u8g_fntpgm_uint8_t fontpage_212_217_217[45] U8G_FONT_SECTION("fontpage_212_217_217") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0x40,0x2a,0xa0,0xf4,0x40,0x27,0xc0,0x38, 0x20,0x27,0xc0,0x64,0x40,0xa7,0xc0,0x24,0x40,0x22,0x80,0x2f,0xe0}; -const u8g_fntpgm_uint8_t fontpage_214_226_226[45] U8G_FONT_SECTION("fontpage_214_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, +const u8g_fntpgm_uint8_t fontpage_214_226_227[71] U8G_FONT_SECTION("fontpage_214_226_227") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe3,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0x24,0x00,0x27, - 0x80,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0xff,0xc0}; + 0x80,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0xff,0xc0,0x0b,0x0a,0x14, + 0x0c,0x00,0xff,0xff,0xe0,0x04,0x00,0x04,0x00,0x24,0x00,0x27,0xc0,0x24,0x00,0x24, + 0x00,0x24,0x00,0x24,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_214_229_229[45] U8G_FONT_SECTION("fontpage_214_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x27,0xc0,0x24,0x00,0x24,0x00,0xff, 0xe0,0x04,0x00,0x14,0x40,0x24,0x80,0x41,0x00,0x06,0x00,0xf8,0x00}; const u8g_fntpgm_uint8_t fontpage_215_212_212[45] U8G_FONT_SECTION("fontpage_215_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x84,0x00,0x84,0x00,0x84,0x80,0x85,0x00,0xf6, 0x00,0x84,0x00,0x84,0x00,0x84,0x00,0xb4,0x40,0xc4,0x40,0x83,0xc0}; const u8g_fntpgm_uint8_t fontpage_217_161_161[45] U8G_FONT_SECTION("fontpage_217_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0x80,0x24,0x80,0x84,0x80,0x48,0xe0,0x10, 0x00,0x2f,0xc0,0x24,0x80,0x42,0x80,0xc3,0x00,0x44,0x80,0x58,0x60}; const u8g_fntpgm_uint8_t fontpage_217_226_226[45] U8G_FONT_SECTION("fontpage_217_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x21,0x00,0x8f,0xe0,0x49,0x20,0x19, 0x00,0x2f,0xc0,0x28,0x40,0xca,0x80,0x49,0x00,0x52,0x80,0x6c,0x60}; const u8g_fntpgm_uint8_t fontpage_218_187_187[45] U8G_FONT_SECTION("fontpage_218_187_187") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0xc0,0x27,0x00,0x81,0x00,0x5f,0xe0,0x11, 0x00,0x21,0x00,0x27,0xc0,0xc4,0x40,0x44,0x40,0x47,0xc0,0x44,0x40}; const u8g_fntpgm_uint8_t fontpage_218_203_203[45] U8G_FONT_SECTION("fontpage_218_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xbe,0x20,0x62,0xa0,0x2a,0xa0,0xaa,0xa0,0x6a, 0xa0,0x2a,0xa0,0x2a,0xa0,0xc8,0xa0,0x54,0x20,0x62,0x20,0x40,0xe0}; const u8g_fntpgm_uint8_t fontpage_219_136_136[45] U8G_FONT_SECTION("fontpage_219_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x49,0x20,0x25,0x40,0x81,0x00,0x57,0xe0,0x14, 0x20,0x27,0xe0,0x24,0x20,0xc7,0xe0,0x44,0x20,0x44,0x20,0x44,0x60}; const u8g_fntpgm_uint8_t fontpage_219_225_225[45] U8G_FONT_SECTION("fontpage_219_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x25,0x40,0x09,0x80,0x82,0x80,0x54, 0x40,0x29,0x20,0x25,0x40,0xc5,0x80,0x49,0x00,0x42,0x80,0x5c,0x60}; const u8g_fntpgm_uint8_t fontpage_220_133_133[45] U8G_FONT_SECTION("fontpage_220_133_133") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x2f,0xe0,0x01,0x00,0x97,0xc0,0x51, 0x00,0x2f,0xe0,0x24,0x40,0xc7,0x40,0x45,0xc0,0x44,0x40,0x44,0xc0}; const u8g_fntpgm_uint8_t fontpage_220_169_169[45] U8G_FONT_SECTION("fontpage_220_169_169") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0x24,0x40,0x07,0xc0,0x94,0x40,0x57, 0xc0,0x20,0x00,0x2f,0xe0,0xca,0xa0,0x4a,0xa0,0x4a,0xa0,0x5f,0xe0}; const u8g_fntpgm_uint8_t fontpage_221_144_144[45] U8G_FONT_SECTION("fontpage_221_144_144") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xe0,0x28,0x80,0x8b,0xe0,0x4a,0x20,0x1b, 0xe0,0x2a,0x20,0x2b,0xe0,0xc8,0x80,0x4a,0xc0,0x54,0xa0,0x69,0xa0}; const u8g_fntpgm_uint8_t fontpage_223_192_192[45] U8G_FONT_SECTION("fontpage_223_192_192") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x80,0x3e,0x80,0x12,0xe0,0x9e,0xa0,0x53, 0xa0,0x3e,0xa0,0x28,0xa0,0xdf,0xa0,0x4a,0x40,0x52,0xa0,0x65,0x20}; const u8g_fntpgm_uint8_t fontpage_224_239_239[45] U8G_FONT_SECTION("fontpage_224_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x00,0x17,0xe0,0x54,0x80,0x58,0x80,0x50, 0x80,0x90,0x80,0x10,0x80,0x10,0x80,0x28,0x80,0x44,0x80,0x81,0x80}; const u8g_fntpgm_uint8_t fontpage_225_185_185[45] U8G_FONT_SECTION("fontpage_225_185_185") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x07,0xc0,0x04,0x00,0x3f, 0x80,0x20,0x80,0x20,0x80,0x3f,0x80,0x00,0x00,0x52,0x40,0x89,0x20}; const u8g_fntpgm_uint8_t fontpage_225_237_237[45] U8G_FONT_SECTION("fontpage_225_237_237") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0xf7,0x80,0x22,0x80,0x32,0x80,0x66, 0x80,0xa3,0x80,0x24,0xa0,0x68,0x60,0x00,0x00,0x52,0x40,0x89,0x20}; const u8g_fntpgm_uint8_t fontpage_228_199_199[45] U8G_FONT_SECTION("fontpage_228_199_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x21,0x00,0x3f,0xe0,0x20, 0x00,0x20,0x00,0x3f,0x80,0x20,0x80,0x20,0x80,0x40,0x80,0x80,0x80}; const u8g_fntpgm_uint8_t fontpage_228_249_249[45] U8G_FONT_SECTION("fontpage_228_249_249") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0xa7,0xc0,0xf1,0x00,0xa1,0x00,0xaf, 0xe0,0x30,0x80,0x6f,0xe0,0xa4,0x80,0x22,0x80,0x20,0x80,0x23,0x80}; const u8g_fntpgm_uint8_t fontpage_231_135_135[45] U8G_FONT_SECTION("fontpage_231_135_135") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x88,0x40,0x52,0x80,0x0c, 0x00,0x2a,0x80,0xdf,0x40,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_234_168_168[45] U8G_FONT_SECTION("fontpage_234_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x44,0x40,0x44,0x40,0x7f,0xc0,0x44, 0x40,0x44,0x40,0x7f,0xc0,0x44,0x40,0x44,0x40,0x84,0x40,0x84,0xc0}; const u8g_fntpgm_uint8_t fontpage_234_181_181[45] U8G_FONT_SECTION("fontpage_234_181_181") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb5,0xb5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb5,0xb5,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0xff,0x80,0x88,0x80,0xff, 0x80,0x88,0x80,0x88,0x80,0xff,0x80,0x08,0x40,0x08,0x40,0x07,0xc0}; const u8g_fntpgm_uint8_t fontpage_236_253_253[34] U8G_FONT_SECTION("fontpage_236_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x08,0x0b,0x0b,0x0c,0x02,0xff,0x10,0x20,0xff,0x81,0x81,0xff,0x81,0x81,0x81, 0xff,0x81}; const u8g_fntpgm_uint8_t fontpage_237_132_132[45] U8G_FONT_SECTION("fontpage_237_132_132") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x22,0x00,0x42,0x00,0xf7,0xc0,0x98,0x40,0x90, 0x40,0xf4,0x40,0x92,0x40,0x92,0x40,0x90,0x40,0xf0,0x40,0x91,0x80}; const u8g_fntpgm_uint8_t fontpage_237_244_244[45] U8G_FONT_SECTION("fontpage_237_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x04,0x00,0x3f,0x80,0x20, 0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0x20,0x80,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_238_129_129[45] U8G_FONT_SECTION("fontpage_238_129_129") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x81,0x81,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x81,0x81,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x14,0x80,0x25,0x60,0x46,0x20,0x1f, 0x80,0x30,0x80,0xdf,0x80,0x10,0x80,0x1f,0x80,0x10,0x80,0x1f,0x80}; const u8g_fntpgm_uint8_t fontpage_238_160_160[45] U8G_FONT_SECTION("fontpage_238_160_160") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x07,0xe0,0xf4,0x20,0x97,0xe0,0xf4,0x80,0x94, 0x80,0x97,0xe0,0xf4,0x80,0x94,0x80,0xf4,0xa0,0x96,0x60,0x04,0x20}; +const u8g_fntpgm_uint8_t fontpage_240_238_238[45] U8G_FONT_SECTION("fontpage_240_238_238") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xee,0xee,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0xf3,0xc0,0x24,0x80,0x4f,0xe0,0xf5, + 0x20,0x57,0xe0,0x55,0x20,0x57,0xe0,0x75,0x20,0x45,0x20,0x08,0x60}; const u8g_fntpgm_uint8_t fontpage_243_239_239[45] U8G_FONT_SECTION("fontpage_243_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x18,0x00,0xe3,0xe0,0x22,0x20,0xfa,0x20,0x22, 0x20,0x73,0xe0,0x68,0x00,0xa2,0x40,0xa2,0x40,0x24,0x20,0x28,0x20}; const u8g_fntpgm_uint8_t fontpage_243_251_251[45] U8G_FONT_SECTION("fontpage_243_251_251") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xe3,0xe0,0x24,0x20,0xfa,0x40,0x21, 0x80,0x36,0x80,0x29,0xe0,0x62,0x20,0xa5,0x40,0x20,0x80,0x27,0x00}; const u8g_fntpgm_uint8_t fontpage_245_239_239[45] U8G_FONT_SECTION("fontpage_245_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x81,0x00,0x45,0x20,0xf7,0xe0,0x00,0x00,0xaf, 0xe0,0xa1,0x00,0xaf,0xe0,0x4a,0xa0,0x6a,0xa0,0x8a,0xa0,0x08,0x60}; const u8g_fntpgm_uint8_t fontpage_246_201_201[45] U8G_FONT_SECTION("fontpage_246_201_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x7b,0xe0,0x94,0x80,0x7f,0xc0,0x04, 0x00,0xff,0xe0,0x01,0x00,0x7f,0xc0,0x11,0x00,0x09,0x00,0x03,0x00}; const u8g_fntpgm_uint8_t fontpage_247_161_161[45] U8G_FONT_SECTION("fontpage_247_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x3d,0xe0,0x52,0x80,0xff,0xe0,0x80, 0x20,0x3f,0x80,0x20,0x80,0x3f,0xc0,0x20,0x40,0x20,0x40,0x3f,0xc0}; const u8g_fntpgm_uint8_t fontpage_248_251_251[45] U8G_FONT_SECTION("fontpage_248_251_251") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x80,0x15,0x00,0xff,0xe0,0x15,0x00,0x24, 0x80,0x40,0x40,0x04,0x00,0xff,0xe0,0x0a,0x00,0x11,0x00,0xe0,0xe0}; const u8g_fntpgm_uint8_t fontpage_250_171_171[45] U8G_FONT_SECTION("fontpage_250_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x51,0x40,0x5d,0x80,0x51,0x20,0xfd, 0xe0,0x08,0x80,0x3f,0x00,0x08,0x80,0x7f,0xc0,0x24,0x80,0xcc,0x60}; const u8g_fntpgm_uint8_t fontpage_253_162_162[45] U8G_FONT_SECTION("fontpage_253_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xc0,0x41,0x00,0x51,0x00,0xe1, 0x00,0x21,0x00,0x41,0x00,0xf1,0x00,0x01,0x00,0x31,0x00,0xcf,0xe0}; const u8g_fntpgm_uint8_t fontpage_253_191_191[45] U8G_FONT_SECTION("fontpage_253_191_191") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x80,0x22,0x40,0x43,0xc0,0x4e,0x00,0xe3, 0xe0,0x2e,0x00,0x42,0x40,0xf2,0x80,0x09,0x20,0x32,0xa0,0xcc,0x60}; const u8g_fntpgm_uint8_t fontpage_253_198_198[45] U8G_FONT_SECTION("fontpage_253_198_198") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc6,0xc6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc6,0xc6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xe0,0x44,0xa0,0x54,0xa0,0xe4, 0xa0,0x27,0xe0,0x44,0xa0,0xf4,0xa0,0x04,0xa0,0x37,0xe0,0xc4,0x20}; const u8g_fntpgm_uint8_t fontpage_253_200_200[45] U8G_FONT_SECTION("fontpage_253_200_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xc0,0x54,0x40,0xea,0x80,0x21, 0x00,0x42,0x80,0xec,0x60,0x01,0x00,0x30,0xc0,0xc3,0x00,0x00,0xc0}; const u8g_fntpgm_uint8_t fontpage_253_223_223[45] U8G_FONT_SECTION("fontpage_253_223_223") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x42,0x00,0x54,0x40,0xef, 0xe0,0x22,0xa0,0x42,0x80,0xf2,0x80,0x02,0xa0,0x34,0xa0,0xc8,0xe0}; const u8g_fntpgm_uint8_t fontpage_253_231_231[45] U8G_FONT_SECTION("fontpage_253_231_231") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x80,0x26,0xa0,0x45,0xc0,0x54,0x80,0xe7, 0xe0,0x24,0x80,0x45,0xc0,0xf6,0xa0,0x04,0x80,0x34,0x80,0xc7,0xe0}; const u8g_fntpgm_uint8_t fontpage_253_234_234[45] U8G_FONT_SECTION("fontpage_253_234_234") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xa0,0x49,0x40,0x57,0xe0,0xe1, 0x00,0x23,0xe0,0x46,0x20,0xf3,0xe0,0x0a,0x20,0x33,0xe0,0xc2,0x20}; const u8g_fntpgm_uint8_t fontpage_253_237_237[45] U8G_FONT_SECTION("fontpage_253_237_237") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xc0,0x41,0x00,0x57,0xe0,0xe4, 0xa0,0x2a,0x80,0x44,0x80,0xef,0xe0,0x01,0x00,0x32,0xc0,0xcc,0x20}; const u8g_fntpgm_uint8_t fontpage_253_255_255[45] U8G_FONT_SECTION("fontpage_253_255_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xc0,0x20,0x40,0x43,0xc0,0xf0,0x40,0x2f, 0xe0,0x41,0x20,0xf5,0x40,0x03,0x80,0x35,0x40,0xc9,0x20,0x03,0x00}; const u8g_fntpgm_uint8_t fontpage_254_150_150[45] U8G_FONT_SECTION("fontpage_254_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x48,0x20,0x5f,0xe0,0xe8, 0x00,0x2f,0xe0,0x4a,0xa0,0xff,0xe0,0x0a,0xa0,0x3a,0xa0,0xc8,0x60}; const u8g_fntpgm_uint8_t fontpage_254_186_186[45] U8G_FONT_SECTION("fontpage_254_186_186") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x41,0x00,0x7b,0xc0,0xa1,0x40,0x21, 0x40,0xff,0xe0,0x21,0x00,0xa9,0x00,0xaa,0x80,0xfa,0x40,0x04,0x20}; const u8g_fntpgm_uint8_t fontpage_254_209_209[45] U8G_FONT_SECTION("fontpage_254_209_209") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x80,0x40,0x91,0x40,0xd5,0x40,0xa2, 0x40,0x92,0x40,0xad,0x40,0xc5,0x40,0x88,0x40,0x80,0x40,0x81,0xc0}; const u8g_fntpgm_uint8_t fontpage_254_238_238[45] U8G_FONT_SECTION("fontpage_254_238_238") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xee,0xee,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xee,0xee,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x4a,0x40,0x7f,0xc0,0x04,0x00,0xff, 0xe0,0x20,0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_254_242_242[45] U8G_FONT_SECTION("fontpage_254_242_242") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xe0,0x49,0x20,0x7f,0xe0,0x04,0x40,0x3f, 0x80,0x05,0x00,0xff,0xe0,0x30,0x80,0xdf,0x80,0x10,0x80,0x1f,0x80}; const u8g_fntpgm_uint8_t fontpage_256_234_234[45] U8G_FONT_SECTION("fontpage_256_234_234") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x40,0xfa,0x80,0x57,0xc0,0x54,0x40,0x74, 0x40,0x57,0xc0,0x71,0x00,0x5a,0xa0,0xf6,0xa0,0x1a,0x40,0x11,0xc0}; const u8g_fntpgm_uint8_t fontpage_259_234_234[34] U8G_FONT_SECTION("fontpage_259_234_234") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, 0x00,0x07,0x0b,0x0b,0x0c,0x02,0xff,0x20,0xfe,0x82,0x82,0xfe,0x82,0xfe,0x82,0x82, 0xfe,0x82}; const u8g_fntpgm_uint8_t fontpage_263_220_220[45] U8G_FONT_SECTION("fontpage_263_220_220") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x11,0x00,0x01,0xc0,0x7e, 0x80,0x28,0x80,0x15,0x00,0xff,0xe0,0x15,0x00,0x24,0x80,0xc4,0x60}; const u8g_fntpgm_uint8_t fontpage_265_221_221[45] U8G_FONT_SECTION("fontpage_265_221_221") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x11,0x00,0x52,0x00,0x53, 0xc0,0x55,0x00,0x10,0x80,0x7f,0xc0,0x4a,0x40,0x4a,0x40,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_272_204_204[45] U8G_FONT_SECTION("fontpage_272_204_204") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xc0,0x40,0x00,0x80,0x00,0x10,0x00,0x2f, 0xe0,0x60,0x80,0xa0,0x80,0x20,0x80,0x20,0x80,0x20,0x80,0x23,0x80}; const u8g_fntpgm_uint8_t fontpage_273_171_171[45] U8G_FONT_SECTION("fontpage_273_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x80,0x20,0x80,0xff,0xe0,0x14,0xa0,0x2c, 0x80,0x77,0xe0,0xad,0x40,0x25,0x40,0x24,0x80,0x29,0x40,0x36,0x20}; const u8g_fntpgm_uint8_t fontpage_273_197_197[45] U8G_FONT_SECTION("fontpage_273_197_197") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x9f,0xe0,0x51,0x00,0x31,0x00,0xd7, 0xc0,0x12,0x00,0xff,0xe0,0x0c,0x40,0x32,0x80,0xd1,0x00,0x18,0xe0}; const u8g_fntpgm_uint8_t fontpage_275_210_210[45] U8G_FONT_SECTION("fontpage_275_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x10,0x00,0x1f,0x00,0x22,0x00,0x7f,0xc0,0xa4, 0x40,0x3f,0xc0,0x24,0x40,0x3f,0xc0,0x24,0x40,0x45,0x40,0x80,0x80}; const u8g_fntpgm_uint8_t fontpage_279_161_161[45] U8G_FONT_SECTION("fontpage_279_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x21,0x00,0x01,0x00,0x0f,0xe0,0xe1, 0x00,0x21,0x00,0x21,0x00,0x29,0x00,0x31,0x00,0x21,0x00,0x01,0x00}; const u8g_fntpgm_uint8_t fontpage_279_174_174[45] U8G_FONT_SECTION("fontpage_279_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x21,0x40,0x05,0x40,0x04,0x40,0xe4, 0x40,0x22,0x80,0x22,0x80,0x29,0x00,0x32,0x80,0x24,0x40,0x08,0x20}; const u8g_fntpgm_uint8_t fontpage_279_190_190[45] U8G_FONT_SECTION("fontpage_279_190_190") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0x80,0x24,0x80,0x04,0x80,0x08,0xe0,0xe0, 0x00,0x2f,0xc0,0x24,0x40,0x22,0x80,0x31,0x00,0x22,0x80,0x1c,0x60}; const u8g_fntpgm_uint8_t fontpage_279_213_213[45] U8G_FONT_SECTION("fontpage_279_213_213") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x40,0x21,0x20,0x1f,0xe0,0x01,0x00,0xef, 0x00,0x25,0x00,0x25,0x00,0x24,0xa0,0x26,0xa0,0x38,0x60,0x20,0x20}; const u8g_fntpgm_uint8_t fontpage_279_239_239[45] U8G_FONT_SECTION("fontpage_279_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0x24,0x40,0x04,0x40,0x07,0xc0,0xe0, 0x00,0x27,0xc0,0x21,0x00,0x2f,0xe0,0x32,0x80,0x24,0x40,0x08,0x20}; const u8g_fntpgm_uint8_t fontpage_279_247_247[45] U8G_FONT_SECTION("fontpage_279_247_247") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x2f,0xe0,0x21,0x00,0x07,0xc0,0xe1, 0x00,0x2f,0xe0,0x24,0x40,0x27,0xc0,0x24,0x40,0x37,0xc0,0x24,0x40}; const u8g_fntpgm_uint8_t fontpage_280_131_131[45] U8G_FONT_SECTION("fontpage_280_131_131") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xe0,0x29,0x20,0x0b,0xa0,0xe9,0x20,0x2f, 0xe0,0x28,0x20,0x2b,0xa0,0x2a,0xa0,0x3b,0xa0,0x28,0x20,0x10,0xe0}; const u8g_fntpgm_uint8_t fontpage_282_165_165[45] U8G_FONT_SECTION("fontpage_282_165_165") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa5,0xa5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa5,0xa5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf9,0x00,0x89,0x00,0xa9,0xe0,0xa9,0x40,0xab, 0x40,0xad,0x40,0xa9,0x40,0x21,0x40,0x50,0x80,0x49,0x40,0x8a,0x20}; const u8g_fntpgm_uint8_t fontpage_286_244_244[45] U8G_FONT_SECTION("fontpage_286_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0xf8,0x80,0x47,0xe0,0x64,0xa0,0xa4, 0xa0,0xfc,0xa0,0x27,0xe0,0x3c,0xa0,0xe4,0xa0,0x27,0xe0,0x24,0x20}; const u8g_fntpgm_uint8_t fontpage_286_253_253[45] U8G_FONT_SECTION("fontpage_286_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x7d,0x40,0x11,0x20,0xff,0xe0,0x21, 0x00,0xfd,0x20,0x51,0x40,0x7c,0x80,0x10,0xa0,0xfd,0x60,0x12,0x20}; const u8g_fntpgm_uint8_t fontpage_287_145_145[45] U8G_FONT_SECTION("fontpage_287_145_145") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x23,0xc0,0xfa,0x40,0x43,0xc0,0x60,0x00,0xa7, 0xe0,0xfa,0x40,0x23,0x40,0x3a,0xc0,0xe2,0x60,0x2f,0xc0,0x20,0x40}; const u8g_fntpgm_uint8_t fontpage_287_147_147[45] U8G_FONT_SECTION("fontpage_287_147_147") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x93,0x93,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x93,0x93,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x42,0x80,0xf4,0x40,0x4b,0xa0,0xa0, 0x00,0xfe,0x20,0x2a,0xa0,0x3e,0xa0,0xea,0xa0,0x2e,0xa0,0x2a,0x60}; const u8g_fntpgm_uint8_t fontpage_287_185_185[45] U8G_FONT_SECTION("fontpage_287_185_185") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x21,0x00,0x2f,0xe0,0x01,0x20,0xe1, 0x20,0x21,0x20,0x22,0x20,0x24,0x20,0x28,0xc0,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_287_208_209[73] U8G_FONT_SECTION("fontpage_287_208_209") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0x20,0x00,0x20,0x00,0x0f,0xe0,0xe2, 0x00,0x22,0x80,0x24,0x40,0x2f,0xa0,0x24,0x20,0x50,0x00,0x8f,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x40,0xc0,0x27,0x00,0x24,0x00,0x07,0xe0,0xe4,0x80,0x24,0x80,0x24, 0x80,0x24,0x80,0x28,0x80,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_287_212_212[45] U8G_FONT_SECTION("fontpage_287_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x60,0x27,0x80,0x24,0x00,0x07,0xe0,0xe6, 0x20,0x25,0x40,0x24,0x80,0x29,0x40,0x26,0x20,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_287_216_216[45] U8G_FONT_SECTION("fontpage_287_216_216") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xe0,0x20,0x80,0x21,0x00,0x01,0x00,0xe3, 0x40,0x25,0x20,0x29,0x20,0x21,0x00,0x21,0x00,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_287_219_219[45] U8G_FONT_SECTION("fontpage_287_219_219") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdb,0xdb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdb,0xdb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x80,0x24,0x80,0x2f,0xc0,0x04,0x80,0xe4, 0x80,0x3f,0xe0,0x24,0x80,0x24,0x80,0x28,0x80,0x50,0x80,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_128_128[45] U8G_FONT_SECTION("fontpage_288_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x8f,0xc0,0x48,0x40,0x4f,0xc0,0x08,0x40,0xcf, 0xc0,0x48,0x00,0x4b,0x40,0x48,0x80,0x4e,0x40,0xb0,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_137_137[45] U8G_FONT_SECTION("fontpage_288_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x45,0x00,0x25,0x00,0x27,0xc0,0x09,0x00,0xef, 0xe0,0x22,0x80,0x22,0xa0,0x24,0xa0,0x28,0x60,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_159_159[45] U8G_FONT_SECTION("fontpage_288_159_159") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x3f,0xe0,0x21,0x00,0x0f,0xe0,0xe9, 0x20,0x2f,0xe0,0x23,0x80,0x25,0x40,0x29,0x20,0x51,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_289_232_232[45] U8G_FONT_SECTION("fontpage_289_232_232") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0xe0,0xff,0x20,0x45,0x20,0x29,0x40,0xff, 0x80,0x01,0x40,0x7d,0x20,0x45,0x20,0x45,0xa0,0x7d,0x40,0x45,0x00}; const u8g_fntpgm_uint8_t fontpage_291_202_202[45] U8G_FONT_SECTION("fontpage_291_202_202") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x1f,0xc0,0xe2,0x80,0xa9,0x00,0x72,0x80,0xfd, 0x60,0x31,0x00,0x6f,0xc0,0xa1,0x00,0xaf,0xe0,0x21,0x00,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_291_205_205[45] U8G_FONT_SECTION("fontpage_291_205_205") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0xff,0xe0,0x24,0x80,0x3f, 0x80,0x24,0x80,0x3f,0x80,0x04,0x00,0x7f,0xc0,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_291_207_207[45] U8G_FONT_SECTION("fontpage_291_207_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff, 0xe0,0x24,0x80,0x3f,0x80,0x24,0x80,0x7f,0xc0,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_297_136_136[45] U8G_FONT_SECTION("fontpage_297_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x80,0x40,0x80,0x78,0x80,0x80,0x80,0xfb, 0xe0,0x20,0x80,0xf8,0x80,0x20,0x80,0x28,0x80,0x30,0x80,0x20,0x80}; const u8g_fntpgm_uint8_t fontpage_297_174_174[45] U8G_FONT_SECTION("fontpage_297_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0x47,0xc0,0x79,0x40,0x81,0x40,0xf9, 0x40,0x27,0xc0,0xfa,0x40,0x22,0x40,0x2a,0x40,0x32,0x40,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_298_153_153[45] U8G_FONT_SECTION("fontpage_298_153_153") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x80,0x4f,0xe0,0x72,0x80,0x82,0x80,0xef, 0xe0,0x40,0x00,0xf7,0xc0,0x44,0x40,0x47,0xc0,0x54,0x40,0x67,0xc0}; const u8g_fntpgm_uint8_t fontpage_298_174_174[45] U8G_FONT_SECTION("fontpage_298_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x5c,0x80,0x47,0xe0,0x68,0xa0,0x8b,0xe0,0xfc, 0xa0,0x47,0xe0,0xe4,0x80,0x57,0xe0,0x48,0x80,0x6c,0x80,0x53,0xe0}; const u8g_fntpgm_uint8_t fontpage_298_255_255[45] U8G_FONT_SECTION("fontpage_298_255_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x21,0x00,0x22,0x00,0x24,0x00,0x28,0x00,0x30, 0x00,0xff,0xc0,0x28,0x00,0x24,0x00,0x22,0x00,0x29,0x00,0x30,0xc0}; const u8g_fntpgm_uint8_t fontpage_299_237_237[45] U8G_FONT_SECTION("fontpage_299_237_237") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xed,0xed,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xe0,0x20,0x20,0x82,0x20,0x82,0x20,0xbf, 0xa0,0x86,0x20,0x8a,0x20,0x92,0x20,0xa2,0x20,0x86,0x20,0x80,0xe0}; const u8g_fntpgm_uint8_t fontpage_299_244_244[45] U8G_FONT_SECTION("fontpage_299_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x4f,0xc0,0x20,0x40,0x80,0x40,0x9e,0x40,0x92, 0x40,0x9e,0x40,0x92,0x40,0x92,0x40,0x9e,0x40,0x80,0x40,0x81,0xc0}; const u8g_fntpgm_uint8_t fontpage_300_205_205[45] U8G_FONT_SECTION("fontpage_300_205_205") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf2,0x00,0x93,0xe0,0xa6,0x40,0xc1,0x80,0xa6, 0x60,0x91,0x00,0x97,0xe0,0xd5,0x00,0xaf,0xe0,0x81,0x00,0x81,0x00}; const u8g_fntpgm_uint8_t fontpage_300_228_228[45] U8G_FONT_SECTION("fontpage_300_228_228") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf1,0x00,0x92,0x80,0xa4,0x40,0xcb,0xa0,0xa1, 0x00,0x9f,0xe0,0x91,0x00,0xe5,0x40,0x89,0x20,0x91,0x20,0x83,0x00}; const u8g_fntpgm_uint8_t fontpage_302_210_210[45] U8G_FONT_SECTION("fontpage_302_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xc0,0x04,0x00,0x3f,0x80,0x04, 0x00,0xff,0xe0,0x10,0x80,0x1f,0x80,0x10,0x80,0x1f,0x80,0x10,0x80}; const u8g_fntpgm_uint8_t fontpage_302_222_222[45] U8G_FONT_SECTION("fontpage_302_222_222") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x0a,0x00,0x0a,0x00,0xfb,0xe0,0x0a,0x00,0x0a, 0x00,0x7b,0xc0,0x0a,0x00,0x0a,0x00,0xfb,0xe0,0x0a,0x00,0x0a,0x00}; const u8g_fntpgm_uint8_t fontpage_304_249_249[45] U8G_FONT_SECTION("fontpage_304_249_249") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x07,0xe0,0xf9,0x00,0x27,0xe0,0x24,0x20,0x25, 0x20,0x25,0x20,0x25,0x20,0x3d,0x20,0xc1,0x80,0x02,0x40,0x0c,0x20}; const u8g_fntpgm_uint8_t fontpage_305_132_132[45] U8G_FONT_SECTION("fontpage_305_132_132") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfb,0xe0,0x10,0x80,0x63,0xe0,0x22,0x20,0xfa, 0xa0,0x2a,0xa0,0x22,0xa0,0x22,0xa0,0x22,0xa0,0x21,0x40,0x66,0x20}; const u8g_fntpgm_uint8_t fontpage_305_157_157[45] U8G_FONT_SECTION("fontpage_305_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x23,0xe0,0xfc,0x80,0x87,0xe0,0x7a,0x20,0xca, 0xa0,0x32,0xa0,0x4a,0xa0,0xfe,0xa0,0x4a,0xa0,0x79,0x40,0x4e,0x20}; const u8g_fntpgm_uint8_t fontpage_305_206_206[45] U8G_FONT_SECTION("fontpage_305_206_206") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xce,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xce,0xce,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0x80,0x40,0x80,0x42,0x80,0x52,0x80,0x4c, 0x80,0x44,0x80,0x4c,0x80,0x52,0x80,0x62,0xa0,0x80,0x60,0x80,0x20}; const u8g_fntpgm_uint8_t fontpage_306_241_241[45] U8G_FONT_SECTION("fontpage_306_241_241") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x00,0x47,0xc0,0x7c,0x40,0x97,0x40,0xad, 0x40,0x25,0x40,0x27,0x40,0x24,0xc0,0x2c,0x20,0x34,0x20,0x23,0xe0}; const u8g_fntpgm_uint8_t fontpage_308_241_241[45] U8G_FONT_SECTION("fontpage_308_241_241") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf3,0xe0,0x12,0x00,0x52,0x20,0x53,0x20,0x52, 0xa0,0x7a,0x40,0x0a,0x40,0xea,0xa0,0x0b,0x20,0x0a,0x00,0x33,0xe0}; const u8g_fntpgm_uint8_t fontpage_309_216_216[45] U8G_FONT_SECTION("fontpage_309_216_216") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x00,0x00,0x1f,0x00,0x11, 0x00,0x7f,0xc0,0x40,0x40,0x5f,0x40,0x51,0x40,0x5f,0x40,0x40,0xc0}; const u8g_fntpgm_uint8_t fontpage_317_196_196[45] U8G_FONT_SECTION("fontpage_317_196_196") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc4,0xc4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc4,0xc4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x7f,0xc0,0x11,0x00,0xff,0xe0,0x04, 0x00,0x3f,0x80,0x24,0x80,0x3f,0x80,0x24,0x80,0x3f,0x80,0x60,0xc0}; const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510_154_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x08,0x00,0x00, 0x00,0x02,0x07,0x07,0x0c,0x06,0x01,0xc0,0xc0,0x00,0x00,0x00,0xc0,0xc0}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' + FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' FONTDATA_ITEM(156, 157, 157, fontpage_156_157_157), // '丝' -- '丝' FONTDATA_ITEM(156, 170, 170, fontpage_156_170_170), // '个' -- '个' FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' @@ -1099,7 +1102,6 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' FONTDATA_ITEM(171, 183, 183, fontpage_171_183_183), // '喷' -- '喷' FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' - FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' FONTDATA_ITEM(173, 254, 254, fontpage_173_254_254), // '图' -- '图' @@ -1191,7 +1193,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(209, 192, 192, fontpage_209_192_192), // '检' -- '检' FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' - FONTDATA_ITEM(214, 226, 226, fontpage_214_226_226), // '止' -- '止' + FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' FONTDATA_ITEM(217, 161, 161, fontpage_217_161_161), // '没' -- '没' @@ -1217,6 +1219,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' FONTDATA_ITEM(238, 129, 129, fontpage_238_129_129), // '省' -- '省' FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' + FONTDATA_ITEM(240, 238, 238, fontpage_240_238_238), // '确' -- '确' FONTDATA_ITEM(243, 239, 239, fontpage_243_239_239), // '积' -- '积' FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h index e1bb97ea3d..20f5acda52 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h @@ -5,1111 +5,1236 @@ */ #include -const u8g_fntpgm_uint8_t fontpage_64_157_157[26] U8G_FONT_SECTION("fontpage_64_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x07,0x00,0x00, - 0x00,0x05,0x03,0x03,0x06,0x00,0x04,0xd8,0x48,0x90}; const u8g_fntpgm_uint8_t fontpage_69_191_191[28] U8G_FONT_SECTION("fontpage_69_191_191") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x05,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x08,0x18,0x28,0x48,0xf8}; const u8g_fntpgm_uint8_t fontpage_156_128_128[27] U8G_FONT_SECTION("fontpage_156_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x06,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x06,0x00,0x00, 0x00,0x0b,0x02,0x04,0x0c,0x00,0x04,0x00,0x40,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_156_137_139[97] U8G_FONT_SECTION("fontpage_156_137_139") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x8b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x8b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0a,0x14,0x0c,0x00,0xff,0x7f,0xc0,0x00,0x00,0x00,0x00,0x00,0x00,0x3f, 0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xff,0xe0,0x0b,0x0b,0x16,0x0c,0x00, 0xff,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x07,0xc0,0x04,0x00,0x04,0x00,0x04, 0x00,0x04,0x00,0x04,0x00,0xff,0xe0,0x0b,0x0a,0x14,0x0c,0x00,0xff,0xff,0xe0,0x04, 0x00,0x04,0x00,0x06,0x00,0x05,0x00,0x04,0x80,0x04,0x80,0x04,0x00,0x04,0x00,0x04, 0x00}; +const u8g_fntpgm_uint8_t fontpage_156_141_141[45] U8G_FONT_SECTION("fontpage_156_141_141") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x02,0x00,0x02,0x00,0x04,0x00,0x0d, + 0x00,0x14,0x80,0x24,0x40,0x44,0x20,0x84,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_156_166_166[45] U8G_FONT_SECTION("fontpage_156_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x11,0x00,0xff,0xe0,0x0a,0x00,0x4a, 0x40,0x4a,0x40,0x2a,0x40,0x2a,0x80,0x0a,0x00,0x0a,0x00,0xff,0xe0}; -const u8g_fntpgm_uint8_t fontpage_156_170_170[45] U8G_FONT_SECTION("fontpage_156_170_170") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaa,0xaa,0x00,0x0a,0xff,0x00, - 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0x14,0x00,0x22,0x00,0x49, - 0x00,0x88,0xc0,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_156_173_173[45] U8G_FONT_SECTION("fontpage_156_173_173") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0xff,0x80,0x88,0x80,0x88, 0x80,0x88,0x80,0xff,0x80,0x88,0x80,0x08,0x00,0x08,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_156_187_187[45] U8G_FONT_SECTION("fontpage_156_187_187") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x04, 0x00,0x04,0x00,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_156_203_203[45] U8G_FONT_SECTION("fontpage_156_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x04,0x00,0x7f,0xc0,0x00,0x80,0x01, 0x00,0x02,0x00,0x04,0x00,0x08,0x00,0x30,0x00,0x48,0x00,0x87,0xe0}; +const u8g_fntpgm_uint8_t fontpage_157_164_164[45] U8G_FONT_SECTION("fontpage_157_164_164") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x00,0x00,0x11,0x00,0x20, + 0x80,0x51,0x40,0x11,0x00,0x0a,0x00,0x04,0x00,0x1b,0x00,0x60,0xe0}; const u8g_fntpgm_uint8_t fontpage_157_174_174[45] U8G_FONT_SECTION("fontpage_157_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x11,0x00,0x1f,0x00,0x00, 0x00,0xff,0xe0,0x80,0x20,0x1f,0x00,0x11,0x00,0x21,0x20,0xc0,0xe0}; const u8g_fntpgm_uint8_t fontpage_157_228_228[45] U8G_FONT_SECTION("fontpage_157_228_228") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x0a,0x00,0x11,0x00,0x24, 0x80,0xc2,0x60,0x3f,0x80,0x01,0x00,0x0a,0x00,0x04,0x00,0x02,0x00}; +const u8g_fntpgm_uint8_t fontpage_157_246_246[45] U8G_FONT_SECTION("fontpage_157_246_246") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf6,0xf6,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x15,0x00,0x25,0x00,0x2f,0xc0,0x71, + 0x00,0xa1,0x00,0x2f,0xe0,0x21,0x00,0x21,0x00,0x21,0x00,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_157_253_253[45] U8G_FONT_SECTION("fontpage_157_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x80,0x12,0x80,0x22,0x40,0x24,0x40,0x68, 0x20,0xa7,0xc0,0x22,0x40,0x22,0x40,0x22,0x40,0x24,0x40,0x28,0xc0}; const u8g_fntpgm_uint8_t fontpage_158_145_145[45] U8G_FONT_SECTION("fontpage_158_145_145") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x21,0x00,0x3f,0xe0,0x61, 0x00,0xa3,0x80,0x23,0x80,0x25,0x40,0x29,0x20,0x31,0x00,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_158_205_206[73] U8G_FONT_SECTION("fontpage_158_205_206") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xce,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xce,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x11,0x00,0x20,0x00,0x2f,0xe0,0x60, 0x00,0xa4,0x40,0x22,0x40,0x22,0x80,0x20,0x80,0x21,0x00,0x2f,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x10,0xc0,0x1f,0x00,0x29,0x00,0x29,0x00,0x69,0x00,0xaf,0xe0,0x29, 0x00,0x29,0x20,0x2a,0xa0,0x2d,0x60,0x28,0xa0}; const u8g_fntpgm_uint8_t fontpage_158_220_220[45] U8G_FONT_SECTION("fontpage_158_220_220") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x14,0x00,0x14,0x00,0x27,0xe0,0x2a,0x00,0x72, 0x00,0xa3,0xc0,0x22,0x00,0x22,0x00,0x23,0xe0,0x22,0x00,0x22,0x00}; -const u8g_fntpgm_uint8_t fontpage_159_134_134[45] U8G_FONT_SECTION("fontpage_159_134_134") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x04,0x00,0x24,0x80,0x24, - 0x80,0x55,0x40,0x8e,0x20,0x15,0x00,0x24,0x80,0xc4,0x60,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_159_155_155[45] U8G_FONT_SECTION("fontpage_159_155_155") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x14,0x80,0x14,0x80,0x24,0x80,0x2f,0xe0,0x64, 0x80,0xa4,0x80,0x3f,0xe0,0x20,0x00,0x24,0x80,0x28,0x40,0x30,0x20}; const u8g_fntpgm_uint8_t fontpage_159_221_221[45] U8G_FONT_SECTION("fontpage_159_221_221") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x17,0xc0,0x14,0x40,0x24,0x40,0x27,0xc0,0x61, 0x00,0xaf,0xe0,0x21,0x00,0x23,0x80,0x25,0x40,0x29,0x20,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_159_225_225[45] U8G_FONT_SECTION("fontpage_159_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x11,0x00,0x2f,0xe0,0x20,0x00,0x67, 0xc0,0xa0,0x00,0x27,0xc0,0x20,0x00,0x27,0xc0,0x24,0x40,0x27,0xc0}; const u8g_fntpgm_uint8_t fontpage_160_139_139[45] U8G_FONT_SECTION("fontpage_160_139_139") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0xe0,0x29,0x20,0x29,0x20,0x2f,0xe0,0x69, 0x20,0xab,0xa0,0x2a,0xa0,0x2b,0xa0,0x28,0x20,0x2f,0xe0,0x28,0x20}; const u8g_fntpgm_uint8_t fontpage_160_188_188[45] U8G_FONT_SECTION("fontpage_160_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x1f,0xe0,0x22,0x00,0x27,0xc0,0x64, 0x40,0xa7,0xc0,0x24,0x40,0x27,0x40,0x25,0xc0,0x24,0x40,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_160_207_207[45] U8G_FONT_SECTION("fontpage_160_207_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x28,0x20,0x2f,0xe0,0x68, 0x00,0xaf,0xe0,0x2a,0xa0,0x2f,0xe0,0x2a,0xa0,0x3a,0xa0,0x28,0x60}; const u8g_fntpgm_uint8_t fontpage_160_220_220[45] U8G_FONT_SECTION("fontpage_160_220_220") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x3f,0xe0,0x20,0x00,0x4f,0xc0,0x48, 0x40,0xdf,0xe0,0x50,0x20,0x4f,0xc0,0x41,0x00,0x41,0x00,0x47,0x00}; +const u8g_fntpgm_uint8_t fontpage_160_245_245[45] U8G_FONT_SECTION("fontpage_160_245_245") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf5,0xf5,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xe0,0x22,0x00,0x2f,0xc0,0x68, + 0x40,0xaf,0xc0,0x28,0x40,0x2f,0xc0,0x28,0x40,0x2f,0xc0,0x38,0x60}; const u8g_fntpgm_uint8_t fontpage_161_153_153[45] U8G_FONT_SECTION("fontpage_161_153_153") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x80,0x2f,0xc0,0x24,0x80,0x3f,0xe0,0x64, 0x00,0xaf,0xe0,0x29,0x20,0x3f,0xe0,0x29,0x20,0x2f,0xe0,0x29,0x20}; const u8g_fntpgm_uint8_t fontpage_161_179_179[45] U8G_FONT_SECTION("fontpage_161_179_179") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb3,0xb3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb3,0xb3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x3f,0xe0,0x2a,0x40,0x2f,0xc0,0x6a, 0x40,0xbf,0xc0,0x22,0x80,0x3f,0xe0,0x28,0x80,0x24,0x80,0x21,0x80}; +const u8g_fntpgm_uint8_t fontpage_161_190_190[45] U8G_FONT_SECTION("fontpage_161_190_190") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x13,0xe0,0x10,0x80,0x2b,0xe0,0x2a,0x20,0x6f, + 0xe0,0xaa,0x20,0x2b,0xe0,0x2e,0x20,0x2b,0xe0,0x31,0x40,0x26,0x20}; const u8g_fntpgm_uint8_t fontpage_162_178_178[45] U8G_FONT_SECTION("fontpage_162_178_178") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb2,0xb2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb2,0xb2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x28,0x80,0x3d,0xe0,0x40,0xa0,0x5d,0xe0,0xc0, 0x80,0x5d,0xe0,0x43,0x20,0x5d,0xe0,0x55,0x20,0x5d,0xe0,0x55,0x20}; const u8g_fntpgm_uint8_t fontpage_162_197_197[45] U8G_FONT_SECTION("fontpage_162_197_197") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x04,0x00,0xff,0xc0,0x08,0x00,0x11,0x00,0x7f, 0x80,0x12,0x80,0x12,0x00,0x12,0x00,0x22,0x40,0x22,0x40,0xc1,0xc0}; -const u8g_fntpgm_uint8_t fontpage_162_200_200[45] U8G_FONT_SECTION("fontpage_162_200_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, +const u8g_fntpgm_uint8_t fontpage_162_200_201[73] U8G_FONT_SECTION("fontpage_162_200_201") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x24,0x00,0x3f,0xc0,0x44,0x00,0x84, - 0x00,0xff,0xe0,0x12,0x00,0x12,0x00,0x12,0x20,0x22,0x20,0xc1,0xe0}; + 0x00,0xff,0xe0,0x12,0x00,0x12,0x00,0x12,0x20,0x22,0x20,0xc1,0xe0,0x0b,0x0b,0x16, + 0x0c,0x00,0xff,0x04,0x00,0x44,0x40,0x24,0x80,0x04,0x00,0xff,0xe0,0x12,0x00,0x12, + 0x00,0x12,0x20,0x12,0x20,0x22,0x20,0xc1,0xe0}; const u8g_fntpgm_uint8_t fontpage_162_229_229[45] U8G_FONT_SECTION("fontpage_162_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x18,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x0a, 0x00,0x0a,0x00,0x11,0x00,0x11,0x00,0x20,0x80,0x40,0x40,0x80,0x20}; const u8g_fntpgm_uint8_t fontpage_162_232_232[45] U8G_FONT_SECTION("fontpage_162_232_232") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xdf, 0x60,0x04,0x00,0x04,0x00,0x1f,0x00,0x04,0x00,0x04,0x00,0x7f,0xc0}; const u8g_fntpgm_uint8_t fontpage_162_241_241[45] U8G_FONT_SECTION("fontpage_162_241_241") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x7f,0xc0,0x11,0x00,0x11, 0x00,0x11,0x00,0xff,0xe0,0x00,0x00,0x11,0x00,0x20,0x80,0x40,0x40}; const u8g_fntpgm_uint8_t fontpage_162_247_247[45] U8G_FONT_SECTION("fontpage_162_247_247") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0x3f, 0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff,0xe0,0x11,0x00,0xe0,0xe0}; +const u8g_fntpgm_uint8_t fontpage_163_151_151[43] U8G_FONT_SECTION("fontpage_163_151_151") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x97,0x00,0x09,0xff,0x00, + 0x00,0x0b,0x0a,0x14,0x0c,0x00,0xff,0x7f,0xe0,0x40,0x20,0x9f,0x40,0x11,0x00,0x11, + 0x00,0x11,0x00,0x11,0x00,0x21,0x20,0x41,0x20,0x80,0xe0}; const u8g_fntpgm_uint8_t fontpage_163_183_183[45] U8G_FONT_SECTION("fontpage_163_183_183") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x82,0x00,0x42,0x00,0x05,0x00,0x28,0x80,0x32, 0x60,0x41,0x00,0x4f,0xc0,0x80,0x80,0x87,0x00,0x81,0x00,0x00,0x80}; const u8g_fntpgm_uint8_t fontpage_163_198_198[45] U8G_FONT_SECTION("fontpage_163_198_198") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc6,0xc6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc6,0xc6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x0a,0x00,0x89,0x00,0x4f,0xe0,0x59,0x00,0x09, 0x00,0x2f,0xc0,0x29,0x00,0xcf,0xc0,0x49,0x00,0x49,0x00,0x4f,0xe0}; const u8g_fntpgm_uint8_t fontpage_163_250_250[45] U8G_FONT_SECTION("fontpage_163_250_250") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfa,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfa,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x44,0x40,0x44,0x40,0x44,0x40,0x7f, 0xc0,0x04,0x00,0x84,0x20,0x84,0x20,0x84,0x20,0x84,0x20,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_164_134_134[45] U8G_FONT_SECTION("fontpage_164_134_134") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x11,0x00,0x20,0x80,0x20,0x80,0x40, 0x40,0xbf,0xa0,0x08,0x80,0x08,0x80,0x10,0x80,0x20,0x80,0xc3,0x00}; const u8g_fntpgm_uint8_t fontpage_164_151_151[45] U8G_FONT_SECTION("fontpage_164_151_151") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x97,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x97,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7e,0x20,0x10,0x20,0x11,0x20,0x3d,0x20,0x25, 0x20,0x65,0x20,0x99,0x20,0x09,0x20,0x10,0x20,0x20,0x20,0xc0,0xe0}; const u8g_fntpgm_uint8_t fontpage_164_157_157[45] U8G_FONT_SECTION("fontpage_164_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0x27,0xe0,0xf9,0x20,0x11,0x20,0x21, 0x20,0x69,0x20,0xb1,0x20,0x29,0x20,0x22,0x20,0x24,0x20,0x28,0xc0}; const u8g_fntpgm_uint8_t fontpage_164_176_176[45] U8G_FONT_SECTION("fontpage_164_176_176") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfe,0x20,0x10,0x20,0x20,0xa0,0x44,0xa0,0xfe, 0xa0,0x10,0xa0,0x7c,0xa0,0x10,0xa0,0x10,0x20,0x1e,0x20,0xe0,0xe0}; const u8g_fntpgm_uint8_t fontpage_164_182_183[73] U8G_FONT_SECTION("fontpage_164_182_183") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x20,0x50,0xa0,0x7e,0xa0,0x90,0xa0,0xfe, 0xa0,0x10,0xa0,0x7e,0xa0,0x52,0xa0,0x52,0x20,0x56,0x20,0x10,0xe0,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x7e,0x20,0x42,0x20,0x7e,0xa0,0x48,0xa0,0x48,0xa0,0x7e,0xa0,0x6a, 0xa0,0xaa,0xa0,0xaa,0xa0,0x2e,0x20,0x08,0xe0}; const u8g_fntpgm_uint8_t fontpage_164_245_245[45] U8G_FONT_SECTION("fontpage_164_245_245") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf5,0xf5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf5,0xf5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x20,0x28,0x20,0x54,0xa0,0xfe,0xa0,0x44, 0xa0,0x7c,0xa0,0x44,0xa0,0x7c,0xa0,0xc4,0x20,0x44,0x20,0x7c,0xe0}; const u8g_fntpgm_uint8_t fontpage_165_155_155[45] U8G_FONT_SECTION("fontpage_165_155_155") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9b,0x9b,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0x08,0x00,0xff,0x80,0x08, 0x80,0x08,0x80,0x10,0x80,0x10,0x80,0x20,0x80,0x40,0x80,0x87,0x00}; const u8g_fntpgm_uint8_t fontpage_165_160_160[45] U8G_FONT_SECTION("fontpage_165_160_160") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x20,0x00,0xfd,0xe0,0x25,0x20,0x25, 0x20,0x25,0x20,0x25,0x20,0x25,0x20,0x45,0x20,0x55,0xe0,0x89,0x20}; -const u8g_fntpgm_uint8_t fontpage_165_168_168[45] U8G_FONT_SECTION("fontpage_165_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0x79,0x00,0x01,0x00,0x03,0xe0,0xfd, - 0x20,0x21,0x20,0x21,0x20,0x49,0x20,0xfa,0x20,0x0a,0x20,0x04,0xc0}; const u8g_fntpgm_uint8_t fontpage_165_213_213[45] U8G_FONT_SECTION("fontpage_165_213_213") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd5,0xd5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x78,0x80,0x10,0x80,0xfe,0x80,0x55,0xe0,0x7c, 0xa0,0x54,0xa0,0x7c,0xa0,0x10,0xa0,0x7d,0x20,0x11,0x20,0xfe,0x60}; const u8g_fntpgm_uint8_t fontpage_166_150_150[45] U8G_FONT_SECTION("fontpage_166_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x12,0x00,0x22,0x40,0x22,0x80,0x63, 0x00,0xa2,0x00,0x26,0x00,0x2a,0x00,0x22,0x20,0x22,0x20,0x21,0xe0}; const u8g_fntpgm_uint8_t fontpage_166_202_202[45] U8G_FONT_SECTION("fontpage_166_202_202") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x44,0x40,0x24,0x80,0x15,0x00,0x7f, 0xc0,0x04,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_166_212_212[45] U8G_FONT_SECTION("fontpage_166_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x27,0xc0,0x22,0x40,0xfa,0x40,0x24, 0x80,0x24,0x80,0x3f,0xe0,0x2a,0xa0,0x2a,0xa0,0x33,0x20,0x24,0x40}; const u8g_fntpgm_uint8_t fontpage_166_225_225[45] U8G_FONT_SECTION("fontpage_166_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x0f,0x80,0x08,0x00,0x08,0x00,0xff, 0xe0,0x08,0x00,0x0a,0x00,0x09,0x00,0x08,0x80,0x08,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_166_240_240[45] U8G_FONT_SECTION("fontpage_166_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x10,0x00,0xe7,0xc0,0x84,0x40,0x84,0x40,0xf4, 0x40,0x84,0x40,0x84,0x40,0x94,0x40,0xe5,0x80,0x84,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_166_248_248[45] U8G_FONT_SECTION("fontpage_166_248_248") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0x7d,0xe0,0x91,0x20,0x11,0x20,0xff, 0x20,0x11,0x20,0x5d,0x20,0x51,0x20,0x51,0xa0,0x5d,0x40,0xe1,0x00}; +const u8g_fntpgm_uint8_t fontpage_166_251_251[45] U8G_FONT_SECTION("fontpage_166_251_251") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x28,0x00,0x25,0xe0,0x53,0x20,0x99,0x20,0x25, + 0x20,0x43,0x20,0xbd,0x20,0x25,0xa0,0x25,0x40,0x3d,0x00,0x25,0x00}; const u8g_fntpgm_uint8_t fontpage_167_159_159[45] U8G_FONT_SECTION("fontpage_167_159_159") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0xe0,0x22,0x00,0x2f,0xc0,0x28,0x40,0x2f, 0xc0,0x28,0x40,0x2f,0xc0,0x22,0x00,0x2a,0x80,0x52,0x60,0xa6,0x20}; +const u8g_fntpgm_uint8_t fontpage_167_205_205[45] U8G_FONT_SECTION("fontpage_167_205_205") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0xc0,0x3e,0x00,0x20,0x00,0x20,0x00,0x3f, + 0xc0,0x28,0x80,0x25,0x00,0x22,0x00,0x45,0x00,0x48,0x80,0xb0,0x60}; const u8g_fntpgm_uint8_t fontpage_167_214_214[45] U8G_FONT_SECTION("fontpage_167_214_214") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfc,0x00,0x4b,0xe0,0x4a,0x20,0x7a,0x20,0x49, 0x40,0x79,0x40,0x48,0x80,0x4c,0x80,0xf9,0x40,0x0a,0x40,0x0c,0x20}; const u8g_fntpgm_uint8_t fontpage_167_240_240[45] U8G_FONT_SECTION("fontpage_167_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x10,0x00,0x22,0x00,0x41,0x00,0xff, 0x80,0x00,0x80,0x7f,0x00,0x41,0x00,0x41,0x00,0x41,0x00,0x7f,0x00}; const u8g_fntpgm_uint8_t fontpage_168_136_136[45] U8G_FONT_SECTION("fontpage_168_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xdf, 0x60,0x00,0x00,0x3f,0x80,0x20,0x80,0x20,0x80,0x3f,0x80,0x20,0x80}; +const u8g_fntpgm_uint8_t fontpage_168_166_166[45] U8G_FONT_SECTION("fontpage_168_166_166") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x04,0x00,0x0d,0x80,0x34,0x40,0xc4, + 0x20,0x04,0x00,0x3f,0xc0,0x20,0x40,0x20,0x40,0x3f,0xc0,0x20,0x40}; +const u8g_fntpgm_uint8_t fontpage_168_202_202[45] U8G_FONT_SECTION("fontpage_168_202_202") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x00,0x24,0x00,0x3f,0xc0,0x44,0x00,0x04, + 0x00,0xff,0xe0,0x00,0x00,0x3f,0x80,0x20,0x80,0x20,0x80,0x3f,0x80}; const u8g_fntpgm_uint8_t fontpage_168_253_253[45] U8G_FONT_SECTION("fontpage_168_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x0a,0x00,0x11,0x00,0xee,0xe0,0x00, 0x00,0x7b,0xc0,0x4a,0x40,0x4a,0x40,0x7a,0x40,0x4a,0xc0,0x02,0x00}; const u8g_fntpgm_uint8_t fontpage_169_140_140[45] U8G_FONT_SECTION("fontpage_169_140_140") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x0c,0x00,0x70,0x00,0x11,0xe0,0xfd,0x20,0x11, 0x20,0x39,0x20,0x35,0x20,0x55,0x20,0x91,0x20,0x11,0xe0,0x10,0x00}; const u8g_fntpgm_uint8_t fontpage_170_223_223[45] U8G_FONT_SECTION("fontpage_170_223_223") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x7d,0x00,0x45,0xe0,0x7d,0x40,0x43, 0x40,0x5d,0x40,0x55,0x40,0x54,0x80,0x94,0x80,0x9d,0x40,0x82,0x20}; const u8g_fntpgm_uint8_t fontpage_171_174_174[45] U8G_FONT_SECTION("fontpage_171_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xf3,0xc0,0x92,0x40,0x92,0x40,0xff,0xc0,0x44, 0x80,0x7f,0x80,0x44,0x80,0x7f,0x80,0x04,0x00,0xff,0xc0,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_172_180_180[45] U8G_FONT_SECTION("fontpage_172_180_180") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb4,0xb4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb4,0xb4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0xa0,0xeb,0xc0,0xaa,0xa0,0xbf,0xe0,0xa4, 0x80,0xaf,0xe0,0xf9,0x20,0x0f,0xe0,0x09,0x20,0x0f,0xe0,0x11,0x20}; +const u8g_fntpgm_uint8_t fontpage_172_232_232[45] U8G_FONT_SECTION("fontpage_172_232_232") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7b,0xc0,0x4a,0x40,0x4a,0x40,0x7b,0xc0,0x04, + 0x80,0xff,0xe0,0x11,0x00,0xfb,0xe0,0x4a,0x40,0x4a,0x40,0x7b,0xc0}; const u8g_fntpgm_uint8_t fontpage_172_244_244[45] U8G_FONT_SECTION("fontpage_172_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0xef,0xe0,0xa5,0x40,0xaf,0xe0,0xa4, 0x40,0xa7,0xc0,0xe4,0x40,0x07,0xc0,0x04,0x40,0x07,0xc0,0x0c,0x60}; const u8g_fntpgm_uint8_t fontpage_173_222_222[45] U8G_FONT_SECTION("fontpage_173_222_222") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x80,0x40,0x80,0x40,0x9e,0x40,0x92, 0x40,0x92,0x40,0x9e,0x40,0x92,0x40,0x80,0x40,0xff,0xc0,0x80,0x40}; const u8g_fntpgm_uint8_t fontpage_173_224_224[45] U8G_FONT_SECTION("fontpage_173_224_224") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x84,0x20,0x84,0x20,0xbf,0xa0,0x84, 0x20,0x84,0x20,0x8a,0x20,0x91,0x20,0xa0,0xa0,0x80,0x20,0xff,0xe0}; +const u8g_fntpgm_uint8_t fontpage_173_250_250[45] U8G_FONT_SECTION("fontpage_173_250_250") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfa,0x00,0x0a,0xff,0x00, + 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x88,0x40,0x88,0x40,0xff,0x40,0x88, + 0x40,0xbe,0x40,0xa2,0x40,0xa2,0x40,0xbe,0x40,0x80,0x40,0xff,0xc0}; const u8g_fntpgm_uint8_t fontpage_174_150_150[45] U8G_FONT_SECTION("fontpage_174_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x91,0x20,0x9f,0x20,0x84,0x20,0xff, 0xe0,0xaa,0xa0,0xae,0xa0,0xa0,0xa0,0xbf,0xa0,0x80,0x20,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_174_168_168[45] U8G_FONT_SECTION("fontpage_174_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x08,0x00,0xff,0xc0,0x10,0x00,0x22, 0x00,0x62,0x00,0xaf,0x80,0x22,0x00,0x22,0x00,0x22,0x00,0x3f,0xc0}; const u8g_fntpgm_uint8_t fontpage_175_139_139[45] U8G_FONT_SECTION("fontpage_175_139_139") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7e,0x40,0x29,0x40,0x29,0x40,0xff,0x40,0x29, 0x40,0x28,0x40,0x4c,0xc0,0x04,0x00,0x3f,0x80,0x04,0x00,0xff,0xe0}; +const u8g_fntpgm_uint8_t fontpage_175_247_247[45] U8G_FONT_SECTION("fontpage_175_247_247") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0xf9,0x00,0x27,0xc0,0xf9,0x40,0x55, + 0x40,0xfb,0x40,0x21,0x40,0xf9,0xc0,0x22,0x40,0x24,0x20,0x28,0x20}; const u8g_fntpgm_uint8_t fontpage_176_202_202[45] U8G_FONT_SECTION("fontpage_176_202_202") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x2f,0xe0,0x29,0x20,0xff,0xe0,0x29, 0x20,0x2f,0xe0,0x21,0x40,0x33,0xa0,0xe5,0xe0,0x09,0x20,0x10,0xe0}; const u8g_fntpgm_uint8_t fontpage_176_235_235[45] U8G_FONT_SECTION("fontpage_176_235_235") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xeb,0xeb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xeb,0xeb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x21,0x00,0xf7,0xc0,0x24, 0x40,0x27,0x40,0x25,0xc0,0x34,0x40,0xef,0xe0,0x02,0x80,0x0c,0x60}; const u8g_fntpgm_uint8_t fontpage_177_138_138[45] U8G_FONT_SECTION("fontpage_177_138_138") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf9,0x00,0x23,0xc0,0xf9,0x40,0x51,0x40,0xfb, 0x40,0x22,0xc0,0xfc,0x20,0x24,0x20,0x7f,0xc0,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_178_150_150[45] U8G_FONT_SECTION("fontpage_178_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x3d,0x00,0x25,0x00,0x45, 0x80,0xa5,0x40,0x19,0x20,0x09,0x00,0x11,0x00,0x21,0x00,0x41,0x00}; const u8g_fntpgm_uint8_t fontpage_178_154_154[45] U8G_FONT_SECTION("fontpage_178_154_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0x1f,0x00,0x21,0x00,0x52,0x00,0x0c, 0x00,0x34,0x00,0xcf,0x80,0x10,0x80,0x69,0x00,0x06,0x00,0xf8,0x00}; +const u8g_fntpgm_uint8_t fontpage_178_160_160[45] U8G_FONT_SECTION("fontpage_178_160_160") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x79,0xe0,0x8a,0x20,0x50,0x20,0x23, + 0xa0,0xfa,0xa0,0x2a,0xa0,0xcb,0xa0,0x28,0x20,0x11,0x20,0xe0,0xc0}; const u8g_fntpgm_uint8_t fontpage_178_167_167[45] U8G_FONT_SECTION("fontpage_178_167_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0,0x04, 0x00,0x04,0x00,0x0a,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60}; const u8g_fntpgm_uint8_t fontpage_178_169_170[73] U8G_FONT_SECTION("fontpage_178_169_170") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xaa,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xaa,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0xff, 0xe0,0x04,0x00,0x0a,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x0a,0x00,0x0a, 0x00,0x11,0x00,0x19,0x00,0x24,0x80,0xc4,0x60}; const u8g_fntpgm_uint8_t fontpage_178_177_177[45] U8G_FONT_SECTION("fontpage_178_177_177") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x00,0x24,0x00,0x3f,0xc0,0x44,0x00,0x04, 0x00,0xff,0xe0,0x04,0x00,0x0a,0x00,0x11,0x00,0x20,0x80,0xc0,0x60}; const u8g_fntpgm_uint8_t fontpage_179_203_203[45] U8G_FONT_SECTION("fontpage_179_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0xfa,0x40,0x2a,0x20,0x2f, 0xe0,0x48,0x00,0x53,0xe0,0x32,0x20,0x2a,0x20,0x4b,0xe0,0x82,0x20}; +const u8g_fntpgm_uint8_t fontpage_181_146_146[45] U8G_FONT_SECTION("fontpage_181_146_146") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x92,0x92,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x40,0x2f,0xe0,0x24,0x40,0xf7,0xc0,0x54, + 0x40,0x57,0xc0,0x51,0x00,0x2f,0xe0,0x33,0x80,0x4d,0x40,0x89,0x20}; const u8g_fntpgm_uint8_t fontpage_182_208_208[45] U8G_FONT_SECTION("fontpage_182_208_208") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x01,0x00,0x02,0x00,0x04,0x00,0x04, 0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x14,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_182_216_216[45] U8G_FONT_SECTION("fontpage_182_216_216") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0xff,0xe0,0x10,0x00,0x2f,0xc0,0x20, 0x80,0x61,0x00,0xbf,0xe0,0x21,0x00,0x21,0x00,0x21,0x00,0x27,0x00}; const u8g_fntpgm_uint8_t fontpage_183_137_137[45] U8G_FONT_SECTION("fontpage_183_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x88,0x40,0x08, 0x00,0xff,0xe0,0x11,0x00,0x31,0x00,0x0e,0x00,0x09,0x80,0x70,0x60}; const u8g_fntpgm_uint8_t fontpage_183_140_140[45] U8G_FONT_SECTION("fontpage_183_140_140") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x9f,0x40,0x00, 0x00,0x7f,0xe0,0x0a,0x00,0x12,0x00,0x12,0x20,0x22,0x20,0x41,0xe0}; const u8g_fntpgm_uint8_t fontpage_183_154_154[45] U8G_FONT_SECTION("fontpage_183_154_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x80,0x40,0x3f, 0xc0,0x04,0x00,0x24,0x00,0x27,0x80,0x24,0x00,0x54,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_183_162_162[45] U8G_FONT_SECTION("fontpage_183_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x08,0x00,0xff,0xc0,0x90,0x40,0x3f,0x00,0x52, 0x00,0x8c,0x00,0x33,0x00,0xff,0xc0,0x21,0x00,0x21,0x00,0x3f,0x00}; const u8g_fntpgm_uint8_t fontpage_183_185_185[45] U8G_FONT_SECTION("fontpage_183_185_185") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x91,0x20,0x24,0x80,0x4a, 0x40,0x11,0x00,0x20,0x80,0xdf,0x60,0x11,0x00,0x11,0x00,0x1f,0x00}; const u8g_fntpgm_uint8_t fontpage_184_141_141[45] U8G_FONT_SECTION("fontpage_184_141_141") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x28,0x40,0xaa,0x40,0x6c,0x40,0xff,0xe0,0x28, 0x40,0x7d,0x40,0x10,0xc0,0x7c,0x40,0x10,0x40,0x1d,0x40,0xe0,0x80}; const u8g_fntpgm_uint8_t fontpage_184_143_143[45] U8G_FONT_SECTION("fontpage_184_143_143") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0x24,0x80,0x24, 0x40,0x44,0x40,0x44,0x20,0x84,0x20,0x04,0x00,0x14,0x00,0x08,0x00}; const u8g_fntpgm_uint8_t fontpage_184_177_177[45] U8G_FONT_SECTION("fontpage_184_177_177") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xfd,0x40,0x01,0x20,0x7f,0xe0,0x4a, 0x80,0x7a,0x80,0x12,0x80,0x5a,0xa0,0x56,0xa0,0x92,0xa0,0x34,0x60}; const u8g_fntpgm_uint8_t fontpage_187_229_229[41] U8G_FONT_SECTION("fontpage_187_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x09,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x09,0x00,0x00, 0x00,0x0b,0x09,0x12,0x0c,0x00,0x00,0x7f,0xc0,0x04,0x00,0x04,0x00,0x04,0x00,0x04, 0x00,0x04,0x00,0x04,0x00,0x04,0x00,0xff,0xe0}; +const u8g_fntpgm_uint8_t fontpage_187_238_238[45] U8G_FONT_SECTION("fontpage_187_238_238") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xee,0xee,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x80,0x09,0x00,0xff,0xe0,0x04,0x00,0x7f, + 0xc0,0x08,0x00,0xff,0xe0,0x10,0x00,0x2f,0x80,0x42,0x00,0xbf,0xe0}; const u8g_fntpgm_uint8_t fontpage_187_242_242[43] U8G_FONT_SECTION("fontpage_187_242_242") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x09,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x09,0xff,0x00, 0x00,0x0a,0x0a,0x14,0x0c,0x01,0xff,0xff,0x00,0x01,0x00,0x01,0x00,0x81,0x00,0xff, 0x00,0x80,0x00,0x80,0x40,0x80,0x40,0x80,0x40,0x7f,0xc0}; const u8g_fntpgm_uint8_t fontpage_188_243_243[45] U8G_FONT_SECTION("fontpage_188_243_243") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0x24,0x80,0x15,0x00,0x04, 0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_189_138_138[45] U8G_FONT_SECTION("fontpage_189_138_138") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0x7f,0xe0,0x42,0x00,0x42,0x00,0x7f, 0xe0,0x42,0x00,0x47,0x00,0x4a,0x80,0x52,0x40,0xa2,0x20,0x82,0x00}; const u8g_fntpgm_uint8_t fontpage_189_166_166[45] U8G_FONT_SECTION("fontpage_189_166_166") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x49,0x00,0x7f,0xc0,0x49, 0x00,0x4f,0x00,0x40,0x00,0x5f,0x80,0x49,0x00,0x86,0x00,0xb9,0xc0}; const u8g_fntpgm_uint8_t fontpage_189_226_226[45] U8G_FONT_SECTION("fontpage_189_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x55,0x40,0x48,0xa0,0x7d, 0xc0,0x45,0x20,0x5e,0x00,0x51,0xc0,0x5d,0x40,0x84,0x80,0x9b,0x60}; const u8g_fntpgm_uint8_t fontpage_189_250_250[45] U8G_FONT_SECTION("fontpage_189_250_250") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfa,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfa,0xfa,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0xef,0xc0,0x22,0x40,0x5f,0xe0,0xe2, 0x40,0x2f,0xc0,0xa2,0x00,0x6f,0xe0,0x22,0x00,0x52,0x00,0x8f,0xe0}; +const u8g_fntpgm_uint8_t fontpage_190_149_149[45] U8G_FONT_SECTION("fontpage_190_149_149") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x95,0x95,0x00,0x0a,0xff,0x00, + 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xfc,0x40,0x04,0x40,0x04,0x40,0x7c,0x40,0x40, + 0x40,0xfc,0x40,0x04,0x40,0x04,0x40,0x04,0x40,0x28,0x40,0x10,0x40}; const u8g_fntpgm_uint8_t fontpage_191_133_133[45] U8G_FONT_SECTION("fontpage_191_133_133") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x21,0x00,0x47,0xc0,0x91,0x00,0x1f, 0xe0,0x20,0x80,0x6f,0xe0,0xa4,0x80,0x22,0x80,0x20,0x80,0x21,0x80}; const u8g_fntpgm_uint8_t fontpage_191_140_140[45] U8G_FONT_SECTION("fontpage_191_140_140") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x24,0x80,0x47,0x00,0x92,0x40,0x2f, 0xe0,0x64,0x20,0xa7,0xc0,0x2c,0x40,0x32,0x80,0x23,0x80,0x2c,0x60}; const u8g_fntpgm_uint8_t fontpage_191_145_145[45] U8G_FONT_SECTION("fontpage_191_145_145") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x91,0x91,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x1f,0xe0,0x25,0x40,0x45,0x40,0x9a,0x80,0x25, 0x40,0x65,0x40,0xa0,0x00,0x27,0xc0,0x21,0x00,0x21,0x00,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_191_158_158[45] U8G_FONT_SECTION("fontpage_191_158_158") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9e,0x9e,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9e,0x9e,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x40,0x22,0x40,0x45,0xa0,0x99,0x20,0x20, 0x00,0x65,0x00,0xa5,0x00,0x25,0xe0,0x25,0x00,0x2b,0x00,0x31,0xe0}; const u8g_fntpgm_uint8_t fontpage_191_169_169[45] U8G_FONT_SECTION("fontpage_191_169_169") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa9,0xa9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x14,0x00,0x27,0xe0,0x4c,0x40,0x97,0xc0,0x24, 0x40,0x67,0xc0,0xa4,0x00,0x27,0xc0,0x2c,0x80,0x33,0x00,0x2c,0xe0}; const u8g_fntpgm_uint8_t fontpage_191_174_174[45] U8G_FONT_SECTION("fontpage_191_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2a,0x80,0x6a,0x80,0xbe,0x80,0x01,0xe0,0x5d, 0x40,0xc3,0x40,0x5d,0x40,0x54,0x80,0x56,0x80,0x55,0x40,0x62,0x20}; const u8g_fntpgm_uint8_t fontpage_191_195_195[45] U8G_FONT_SECTION("fontpage_191_195_195") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x02,0x00,0x12,0x00,0x12,0x00,0x10, 0x40,0x50,0x20,0x50,0x20,0x50,0xa0,0x90,0x80,0x10,0x80,0x0f,0x80}; const u8g_fntpgm_uint8_t fontpage_192_167_167[45] U8G_FONT_SECTION("fontpage_192_167_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x25,0x00,0xb5,0x00,0xaf,0xe0,0xa9, 0x00,0xb1,0x00,0x27,0xc0,0x21,0x00,0x21,0x00,0x21,0x00,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_192_226_226[45] U8G_FONT_SECTION("fontpage_192_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x2f,0xe0,0xb2,0x00,0xaa,0x80,0xa4, 0x80,0xa5,0xa0,0x2a,0xc0,0x30,0x80,0x21,0x40,0x22,0x40,0x24,0x20}; const u8g_fntpgm_uint8_t fontpage_192_239_239[45] U8G_FONT_SECTION("fontpage_192_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20, 0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x54,0x40,0x52,0xa0,0x8f,0x80}; const u8g_fntpgm_uint8_t fontpage_195_182_182[45] U8G_FONT_SECTION("fontpage_195_182_182") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xe0,0xb2,0x80,0xaf,0xe0,0xa4, 0x40,0x27,0xc0,0x24,0x40,0x27,0xc0,0x25,0x40,0x2c,0xa0,0x33,0xa0}; const u8g_fntpgm_uint8_t fontpage_195_201_201[45] U8G_FONT_SECTION("fontpage_195_201_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0x7f,0xe0,0x4a,0x80,0x57,0xe0,0x7c, 0x80,0x57,0xc0,0x54,0x80,0x57,0xe0,0x4a,0x40,0xa8,0xa0,0x4f,0xa0}; const u8g_fntpgm_uint8_t fontpage_196_144_144[45] U8G_FONT_SECTION("fontpage_196_144_144") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x80,0x02,0x40,0x7f,0xe0,0x42,0x00,0x42, 0x00,0x7a,0x40,0x4a,0x40,0x4a,0x80,0x49,0x20,0x52,0xa0,0x84,0x60}; const u8g_fntpgm_uint8_t fontpage_196_182_182[45] U8G_FONT_SECTION("fontpage_196_182_182") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x01,0xc0,0x3e,0x00,0x20,0x00,0x3f,0xc0,0x20, 0x40,0x20,0x40,0x3f,0xc0,0x20,0x00,0x20,0x00,0x40,0x00,0x80,0x00}; const u8g_fntpgm_uint8_t fontpage_196_192_192[45] U8G_FONT_SECTION("fontpage_196_192_192") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x18,0x60,0x63,0x80,0x42,0x00,0x7a,0x00,0x4b, 0xe0,0x4a,0x40,0x7a,0x40,0x42,0x40,0x42,0x40,0x44,0x40,0x88,0x40}; const u8g_fntpgm_uint8_t fontpage_196_199_199[45] U8G_FONT_SECTION("fontpage_196_199_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xe0,0x40,0x20,0x7f,0xe0,0x40, 0x00,0x7d,0xe0,0x44,0x20,0x54,0xa0,0x4c,0x60,0x54,0xa0,0xa9,0x60}; const u8g_fntpgm_uint8_t fontpage_196_203_203[45] U8G_FONT_SECTION("fontpage_196_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x03,0xc0,0x7c,0x00,0x04,0x00,0x7f,0xc0,0x04, 0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00,0x04,0x00,0x0c,0x00}; const u8g_fntpgm_uint8_t fontpage_196_211_211[45] U8G_FONT_SECTION("fontpage_196_211_211") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd3,0xd3,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd3,0xd3,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xe0,0xf8,0x80,0x20,0x80,0x28, 0x80,0x30,0x80,0x60,0x80,0xa0,0x80,0x20,0x80,0x20,0x80,0xe3,0x80}; -const u8g_fntpgm_uint8_t fontpage_196_231_231[45] U8G_FONT_SECTION("fontpage_196_231_231") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe7,0xe7,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x22,0x00,0xff,0x80,0x22,0x80,0x2a, - 0x80,0x36,0x80,0x62,0x80,0xa7,0xa0,0x24,0xa0,0xa8,0xa0,0x50,0x60}; const u8g_fntpgm_uint8_t fontpage_196_249_249[45] U8G_FONT_SECTION("fontpage_196_249_249") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf9,0xf9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x80,0x24,0x80,0xfc,0x80,0x24,0xa0,0x2f, 0xc0,0x34,0x80,0x64,0x80,0xa4,0x80,0x25,0xa0,0x26,0xa0,0xe4,0x60}; const u8g_fntpgm_uint8_t fontpage_197_150_150[45] U8G_FONT_SECTION("fontpage_197_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x40,0x22,0x40,0xf9,0x40,0x20,0x40,0x2a, 0x40,0x31,0x40,0x60,0xe0,0xaf,0x40,0x20,0x40,0x20,0x40,0xe0,0x40}; const u8g_fntpgm_uint8_t fontpage_197_189_189[45] U8G_FONT_SECTION("fontpage_197_189_189") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x20,0x80,0xf8,0x80,0x27,0xe0,0x2c, 0xa0,0x34,0xa0,0x67,0xe0,0xa4,0xa0,0x24,0xa0,0x27,0xe0,0xe4,0x20}; const u8g_fntpgm_uint8_t fontpage_197_212_212[45] U8G_FONT_SECTION("fontpage_197_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x80,0x22,0x40,0xff,0xe0,0x22,0x00,0x2b, 0xc0,0x32,0x40,0x65,0x40,0xa4,0x80,0x28,0x80,0x29,0x40,0xe6,0x20}; const u8g_fntpgm_uint8_t fontpage_198_137_137[45] U8G_FONT_SECTION("fontpage_198_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x20,0x80,0xff,0xe0,0x25,0x20,0x29, 0x00,0x37,0xe0,0x62,0x40,0xa6,0x40,0x21,0x80,0x22,0x80,0xec,0x60}; const u8g_fntpgm_uint8_t fontpage_199_137_137[45] U8G_FONT_SECTION("fontpage_199_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0xe0,0xf9,0x00,0x27,0xc0,0x2c, 0x40,0x37,0xc0,0x64,0x40,0xa7,0xc0,0x21,0x00,0x2f,0xe0,0xe1,0x00}; const u8g_fntpgm_uint8_t fontpage_199_162_162[45] U8G_FONT_SECTION("fontpage_199_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0xe0,0x28,0x20,0xf2,0x80,0x24,0x40,0x29, 0x20,0x31,0x00,0x6f,0xe0,0xa1,0x00,0x25,0x80,0x29,0x40,0xf1,0x20}; +const u8g_fntpgm_uint8_t fontpage_199_165_165[45] U8G_FONT_SECTION("fontpage_199_165_165") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa5,0xa5,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0xf4,0x40,0x22,0x80,0x2f, + 0xe0,0x31,0x00,0x6f,0xe0,0xa2,0x40,0x26,0x80,0x21,0x40,0xee,0x20}; const u8g_fntpgm_uint8_t fontpage_199_167_167[45] U8G_FONT_SECTION("fontpage_199_167_167") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa7,0xa7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0xf8,0x20,0x22,0x80,0x24, 0x40,0x38,0x20,0x67,0xc0,0xa1,0x00,0x21,0x00,0x21,0x00,0xef,0xe0}; +const u8g_fntpgm_uint8_t fontpage_199_208_208[45] U8G_FONT_SECTION("fontpage_199_208_208") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xc0,0x24,0x40,0xff,0xc0,0x24,0x40,0x27, + 0xc0,0x30,0x00,0x6f,0xe0,0xa5,0x00,0x25,0xe0,0x2b,0x00,0xf1,0xe0}; const u8g_fntpgm_uint8_t fontpage_199_210_210[45] U8G_FONT_SECTION("fontpage_199_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0xc0,0x27,0x00,0xf1,0x00,0x2f,0xe0,0x21, 0x00,0x35,0x60,0x69,0x20,0xad,0x60,0x29,0x20,0x29,0x20,0xef,0xe0}; const u8g_fntpgm_uint8_t fontpage_199_219_219[45] U8G_FONT_SECTION("fontpage_199_219_219") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdb,0xdb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdb,0xdb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xc0,0xf4,0x80,0x2f,0xe0,0x2a, 0xa0,0x3a,0xa0,0x6c,0x60,0xa1,0x00,0x2f,0xe0,0x22,0x80,0xec,0x60}; const u8g_fntpgm_uint8_t fontpage_201_199_199[45] U8G_FONT_SECTION("fontpage_201_199_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0xe0,0x2a,0xa0,0xff,0xe0,0x21,0x00,0x2f, 0xe0,0x32,0x80,0xe7,0xc0,0x21,0x00,0x2f,0xe0,0xa1,0x00,0x61,0x00}; const u8g_fntpgm_uint8_t fontpage_201_202_203[73] U8G_FONT_SECTION("fontpage_201_202_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfd,0xc0,0xa9,0x40,0xf9,0x60,0xab,0xc0,0xfd, 0x40,0xa9,0x80,0xab,0x60,0xfe,0x00,0x04,0x00,0xff,0xe0,0x04,0x00,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x29,0x20,0x25,0x40,0xff,0xe0,0x2a,0xa0,0x2b,0x80,0x30,0x00,0xef, 0xe0,0x29,0x20,0x2f,0xe0,0xa9,0x20,0x6f,0xe0}; const u8g_fntpgm_uint8_t fontpage_201_224_224[45] U8G_FONT_SECTION("fontpage_201_224_224") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe0,0xe0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0xfa,0xa0,0x25,0x40,0x2d, 0x60,0x35,0x40,0xe4,0x40,0x27,0xc0,0x24,0x40,0xa7,0xc0,0x68,0x40}; +const u8g_fntpgm_uint8_t fontpage_202_182_182[45] U8G_FONT_SECTION("fontpage_202_182_182") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb6,0xb6,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x12,0x00,0x12,0x00,0x93,0xe0,0x94,0x40,0x9a, + 0x40,0x92,0x40,0xb2,0x80,0xd1,0x00,0x91,0x80,0x12,0x40,0x14,0x20}; const u8g_fntpgm_uint8_t fontpage_202_190_190[45] U8G_FONT_SECTION("fontpage_202_190_190") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbe,0xbe,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x11,0x00,0xfd,0xe0,0x22,0x40,0x25, 0x40,0x39,0x40,0x29,0x40,0x28,0x80,0x49,0x80,0x4a,0x40,0x94,0x20}; const u8g_fntpgm_uint8_t fontpage_202_215_215[45] U8G_FONT_SECTION("fontpage_202_215_215") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd7,0xd7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd7,0xd7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7d,0x00,0x45,0x00,0x7d,0xe0,0x47,0x40,0x7d, 0x40,0x45,0x40,0x7d,0x40,0x45,0x40,0x28,0x80,0x45,0x40,0x86,0x20}; const u8g_fntpgm_uint8_t fontpage_202_244_244[45] U8G_FONT_SECTION("fontpage_202_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x55,0x40,0x7c,0x80,0x39, 0x40,0x56,0x20,0x7f,0xc0,0x04,0x00,0x27,0x80,0x24,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_202_248_248[45] U8G_FONT_SECTION("fontpage_202_248_248") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x7d,0x00,0x55,0xe0,0xff,0x40,0x55, 0x40,0xfd,0x40,0x95,0x40,0xff,0x40,0x28,0x80,0x19,0x40,0xe6,0x20}; const u8g_fntpgm_uint8_t fontpage_203_153_153[45] U8G_FONT_SECTION("fontpage_203_153_153") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x99,0x99,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0xac,0x80,0x72,0x80,0x20,0x80,0xfc, 0x80,0x22,0x80,0x30,0xe0,0x6f,0x80,0xa0,0x80,0x20,0x80,0x20,0x80}; const u8g_fntpgm_uint8_t fontpage_203_156_156[45] U8G_FONT_SECTION("fontpage_203_156_156") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0x9c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0x9c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x40,0x29,0x40,0x44,0xc0,0xb8,0x40,0x12, 0x40,0x7d,0x40,0x10,0x60,0x55,0xc0,0x52,0x40,0x92,0x40,0x30,0x40}; const u8g_fntpgm_uint8_t fontpage_203_176_176[45] U8G_FONT_SECTION("fontpage_203_176_176") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x60,0xfd,0x80,0x45,0x00,0x29,0x00,0xfd, 0xe0,0x11,0x40,0xfd,0x40,0x11,0x40,0x55,0x40,0x92,0x40,0x34,0x40}; +const u8g_fntpgm_uint8_t fontpage_203_183_183[45] U8G_FONT_SECTION("fontpage_203_183_183") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb7,0xb7,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xaa,0x40,0xfd,0x80,0x95,0x00,0xab,0x00,0xff, + 0xe0,0xa9,0x40,0xab,0x40,0xfd,0x40,0x95,0x40,0xab,0x40,0xfe,0x40}; const u8g_fntpgm_uint8_t fontpage_203_188_188[45] U8G_FONT_SECTION("fontpage_203_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x10,0x80,0xfd,0x40,0x21,0x40,0x3a, 0x20,0x2c,0x80,0x28,0x40,0x28,0x40,0x49,0x00,0x48,0x80,0x98,0x40}; +const u8g_fntpgm_uint8_t fontpage_204_135_135[45] U8G_FONT_SECTION("fontpage_204_135_135") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0xc0,0x20,0x40,0x3f,0xc0,0x20,0x40,0x3f, + 0xc0,0x79,0x00,0x11,0x00,0xff,0xe0,0x11,0x00,0x21,0x00,0xc1,0x00}; const u8g_fntpgm_uint8_t fontpage_204_142_142[45] U8G_FONT_SECTION("fontpage_204_142_142") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x03,0xe0,0xf2,0x20,0x92,0x20,0x93,0xe0,0xf2, 0x20,0x92,0x20,0x93,0xe0,0xf2,0x20,0x04,0x20,0x08,0xa0,0x30,0x40}; +const u8g_fntpgm_uint8_t fontpage_204_175_175[45] U8G_FONT_SECTION("fontpage_204_175_175") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x1f,0x80,0x10,0x80,0x1f,0x80,0x10,0x80,0x1f, + 0x80,0x00,0x00,0xff,0xe0,0x24,0x00,0x27,0x80,0x54,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_204_194_194[45] U8G_FONT_SECTION("fontpage_204_194_194") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc2,0xc2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc2,0xc2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0xf7,0xc0,0x91,0x00,0x91,0x00,0xff, 0xe0,0x90,0x80,0x9f,0xe0,0x94,0x80,0xf2,0x80,0x00,0x80,0x03,0x80}; const u8g_fntpgm_uint8_t fontpage_205_171_171[45] U8G_FONT_SECTION("fontpage_205_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0xe0,0xff,0x00,0x55,0xe0,0x7d,0x40,0x55, 0x40,0xff,0xc0,0x10,0x40,0x1f,0xc0,0x10,0x40,0x1f,0xc0,0x10,0x40}; const u8g_fntpgm_uint8_t fontpage_205_244_244[45] U8G_FONT_SECTION("fontpage_205_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xe0,0x02,0x00,0x3f,0xc0,0x22,0x40,0x3f, 0xc0,0x22,0x40,0x3f,0xc0,0x0a,0x00,0x04,0x00,0x1b,0x00,0xe0,0xe0}; const u8g_fntpgm_uint8_t fontpage_206_128_128[45] U8G_FONT_SECTION("fontpage_206_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff, 0xe0,0x48,0x00,0x7f,0xc0,0x4a,0x40,0x79,0x80,0xc9,0x80,0x0e,0x60}; const u8g_fntpgm_uint8_t fontpage_206_137_137[45] U8G_FONT_SECTION("fontpage_206_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x08,0x00,0xff,0xe0,0x10,0x00,0x1f,0x80,0x30, 0x80,0x5f,0x80,0x90,0x80,0x1f,0x80,0x10,0x80,0x10,0x80,0x11,0x80}; const u8g_fntpgm_uint8_t fontpage_206_255_255[45] U8G_FONT_SECTION("fontpage_206_255_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0xc0,0x27,0x00,0xfc,0x00,0x24,0x00,0x27, 0xc0,0x74,0x40,0x6e,0x40,0xa5,0x80,0x28,0x80,0x29,0x40,0x36,0x20}; const u8g_fntpgm_uint8_t fontpage_207_241_241[45] U8G_FONT_SECTION("fontpage_207_241_241") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x21,0x00,0xff,0xe0,0x21,0x00,0x71, 0x00,0x69,0x00,0xa7,0xc0,0xa1,0x00,0x21,0x00,0x21,0x00,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_208_161_161[45] U8G_FONT_SECTION("fontpage_208_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x21,0x00,0x2f,0xe0,0xf0,0x00,0x22, 0x80,0x74,0x40,0x6a,0xa0,0xa2,0x80,0x21,0x00,0x22,0x80,0x2c,0x60}; const u8g_fntpgm_uint8_t fontpage_208_188_188[45] U8G_FONT_SECTION("fontpage_208_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xc0,0xf4,0x40,0x2a,0x80,0x21, 0x00,0x72,0x80,0x6c,0x60,0xa7,0xc0,0x24,0x40,0x24,0x40,0x27,0xc0}; const u8g_fntpgm_uint8_t fontpage_209_157_157[45] U8G_FONT_SECTION("fontpage_209_157_157") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x24,0x00,0x27,0xe0,0x5a,0x40,0x51,0x80,0xde, 0x60,0x51,0x00,0x5f,0xe0,0x51,0x00,0x45,0x40,0x49,0x20,0x53,0x20}; +const u8g_fntpgm_uint8_t fontpage_209_196_196[45] U8G_FONT_SECTION("fontpage_209_196_196") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc4,0xc4,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x20,0x80,0x7f,0xc0,0x24, + 0x80,0xff,0xe0,0x24,0x80,0xff,0xe0,0x15,0x00,0x24,0x80,0xc4,0x60}; const u8g_fntpgm_uint8_t fontpage_211_253_253[45] U8G_FONT_SECTION("fontpage_211_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x80,0x2f,0xe0,0xfa,0xa0,0x2f,0xe0,0x2a, 0xa0,0x3f,0xe0,0x64,0x40,0xa7,0xc0,0x24,0x40,0x27,0xc0,0x24,0x40}; const u8g_fntpgm_uint8_t fontpage_212_217_217[45] U8G_FONT_SECTION("fontpage_212_217_217") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0x40,0x2a,0xa0,0xf4,0x40,0x27,0xc0,0x38, 0x20,0x27,0xc0,0x64,0x40,0xa7,0xc0,0x24,0x40,0x22,0x80,0x2f,0xe0}; const u8g_fntpgm_uint8_t fontpage_212_223_223[45] U8G_FONT_SECTION("fontpage_212_223_223") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x25,0x40,0x29,0xa0,0xff,0x40,0x25,0x20,0x6f, 0xe0,0x75,0x40,0xaf,0xe0,0xa5,0x40,0x26,0xa0,0x29,0x60,0x32,0x20}; const u8g_fntpgm_uint8_t fontpage_213_162_162[45] U8G_FONT_SECTION("fontpage_213_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x22,0x80,0xf4,0x40,0x2b,0xa0,0x60, 0x00,0x7e,0xe0,0xaa,0xa0,0xae,0xe0,0x24,0x40,0x2a,0xc0,0x31,0x20}; -const u8g_fntpgm_uint8_t fontpage_214_226_226[45] U8G_FONT_SECTION("fontpage_214_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, +const u8g_fntpgm_uint8_t fontpage_214_226_227[71] U8G_FONT_SECTION("fontpage_214_226_227") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe3,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x04,0x00,0x04,0x00,0x04,0x00,0x24,0x00,0x27, - 0x80,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0xff,0xc0}; + 0x80,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0x24,0x00,0xff,0xc0,0x0b,0x0a,0x14, + 0x0c,0x00,0xff,0xff,0xe0,0x04,0x00,0x04,0x00,0x24,0x00,0x27,0xc0,0x24,0x00,0x24, + 0x00,0x24,0x00,0x24,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_214_229_229[45] U8G_FONT_SECTION("fontpage_214_229_229") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe5,0xe5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x27,0xc0,0x24,0x00,0x24,0x00,0xff, 0xe0,0x04,0x00,0x14,0x40,0x24,0x80,0x41,0x00,0x06,0x00,0xf8,0x00}; const u8g_fntpgm_uint8_t fontpage_214_248_248[45] U8G_FONT_SECTION("fontpage_214_248_248") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x43,0xc0,0xf0,0x40,0x93,0xc0,0xf8,0x40,0x8f, 0xe0,0xfc,0xa0,0x20,0x80,0xbb,0xe0,0xa2,0xa0,0xba,0xe0,0xe0,0x80}; const u8g_fntpgm_uint8_t fontpage_215_188_188[45] U8G_FONT_SECTION("fontpage_215_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0xc0,0xfd,0x40,0x11,0x40,0xff,0x60,0x84, 0x00,0x7b,0xe0,0x01,0x40,0x79,0x40,0x4a,0x80,0x4d,0x40,0x82,0x20}; const u8g_fntpgm_uint8_t fontpage_215_212_212[45] U8G_FONT_SECTION("fontpage_215_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x84,0x00,0x84,0x00,0x84,0x80,0x85,0x00,0xf6, 0x00,0x84,0x00,0x84,0x00,0x84,0x00,0xb4,0x40,0xc4,0x40,0x83,0xc0}; const u8g_fntpgm_uint8_t fontpage_217_146_146[45] U8G_FONT_SECTION("fontpage_217_146_146") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x92,0x92,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x92,0x92,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x23,0xc0,0x84,0x40,0x59,0x40,0x10, 0x80,0x27,0xc0,0x24,0x40,0xc2,0x80,0x41,0x00,0x46,0x80,0x58,0x60}; -const u8g_fntpgm_uint8_t fontpage_218_187_187[45] U8G_FONT_SECTION("fontpage_218_187_187") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbb,0xbb,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0xc0,0x27,0x00,0x81,0x00,0x5f,0xe0,0x11, - 0x00,0x21,0x00,0x27,0xc0,0xc4,0x40,0x44,0x40,0x47,0xc0,0x44,0x40}; const u8g_fntpgm_uint8_t fontpage_219_136_136[45] U8G_FONT_SECTION("fontpage_219_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x49,0x20,0x25,0x40,0x81,0x00,0x57,0xe0,0x14, 0x20,0x27,0xe0,0x24,0x20,0xc7,0xe0,0x44,0x20,0x44,0x20,0x44,0x60}; -const u8g_fntpgm_uint8_t fontpage_219_188_188[45] U8G_FONT_SECTION("fontpage_219_188_188") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbc,0xbc,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x21,0x00,0x8f,0xe0,0x50,0x00,0x17, - 0xc0,0x24,0x40,0x27,0xc0,0xc1,0x00,0x45,0x40,0x49,0x20,0x53,0x20}; const u8g_fntpgm_uint8_t fontpage_219_225_225[45] U8G_FONT_SECTION("fontpage_219_225_225") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe1,0xe1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x25,0x40,0x09,0x80,0x82,0x80,0x54, 0x40,0x29,0x20,0x25,0x40,0xc5,0x80,0x49,0x00,0x42,0x80,0x5c,0x60}; const u8g_fntpgm_uint8_t fontpage_220_133_133[45] U8G_FONT_SECTION("fontpage_220_133_133") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x2f,0xe0,0x01,0x00,0x97,0xc0,0x51, 0x00,0x2f,0xe0,0x24,0x40,0xc7,0x40,0x45,0xc0,0x44,0x40,0x44,0xc0}; const u8g_fntpgm_uint8_t fontpage_220_172_172[45] U8G_FONT_SECTION("fontpage_220_172_172") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4e,0x20,0x2a,0xa0,0x0a,0xa0,0x8e,0xa0,0x5a, 0xa0,0x2e,0xa0,0x2a,0xa0,0xca,0xa0,0x4e,0x20,0x4a,0x20,0x51,0x60}; const u8g_fntpgm_uint8_t fontpage_221_144_144[45] U8G_FONT_SECTION("fontpage_221_144_144") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xe0,0x28,0x80,0x8b,0xe0,0x4a,0x20,0x1b, 0xe0,0x2a,0x20,0x2b,0xe0,0xc8,0x80,0x4a,0xc0,0x54,0xa0,0x69,0xa0}; const u8g_fntpgm_uint8_t fontpage_221_150_150[45] U8G_FONT_SECTION("fontpage_221_150_150") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x96,0x96,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x85,0x00,0x4f,0xe0,0x99,0x00,0x4f,0xc0,0x49, 0x00,0xcf,0xc0,0x49,0x00,0x4f,0xe0,0x04,0x00,0xff,0xe0,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_221_171_171[45] U8G_FONT_SECTION("fontpage_221_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0x25,0x40,0x06,0xc0,0x84,0x40,0x47, 0xc0,0x20,0x00,0x2f,0xe0,0xca,0xa0,0x4a,0xa0,0x4a,0xa0,0x5f,0xe0}; const u8g_fntpgm_uint8_t fontpage_223_192_192[45] U8G_FONT_SECTION("fontpage_223_192_192") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x80,0x3e,0x80,0x12,0xe0,0x9e,0xa0,0x53, 0xa0,0x3e,0xa0,0x28,0xa0,0xdf,0xa0,0x4a,0x40,0x52,0xa0,0x65,0x20}; -const u8g_fntpgm_uint8_t fontpage_224_239_239[45] U8G_FONT_SECTION("fontpage_224_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x10,0x00,0x17,0xe0,0x54,0x80,0x58,0x80,0x50, - 0x80,0x90,0x80,0x10,0x80,0x10,0x80,0x28,0x80,0x44,0x80,0x81,0x80}; const u8g_fntpgm_uint8_t fontpage_226_161_161[45] U8G_FONT_SECTION("fontpage_226_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0x7f,0xe0,0xaa,0x80,0x2a,0x80,0xff, 0xe0,0x2a,0x80,0x2a,0x80,0xff,0xe0,0x12,0x40,0x49,0x20,0x89,0x20}; const u8g_fntpgm_uint8_t fontpage_227_177_177[45] U8G_FONT_SECTION("fontpage_227_177_177") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0xf9,0x00,0x23,0xc0,0xfd,0x40,0x53, 0x40,0xa9,0x40,0xfa,0xe0,0x22,0x20,0xfa,0x40,0x49,0x20,0x89,0x20}; const u8g_fntpgm_uint8_t fontpage_227_200_200[45] U8G_FONT_SECTION("fontpage_227_200_200") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc8,0xc8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2f,0xa0,0x2b,0x40,0xac,0x80,0xb7,0xc0,0xa8, 0x20,0x37,0xc0,0x24,0x40,0x27,0xc0,0x52,0x80,0x49,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_228_199_199[45] U8G_FONT_SECTION("fontpage_228_199_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x21,0x00,0x3f,0xe0,0x20, 0x00,0x20,0x00,0x3f,0x80,0x20,0x80,0x20,0x80,0x40,0x80,0x80,0x80}; +const u8g_fntpgm_uint8_t fontpage_228_233_233[45] U8G_FONT_SECTION("fontpage_228_233_233") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe9,0xe9,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0xa2,0x00,0xa7,0xe0,0xfa,0xa0,0xa2, + 0xa0,0x32,0xa0,0x64,0xa0,0xa9,0x20,0x22,0x20,0x25,0x20,0x28,0xc0}; const u8g_fntpgm_uint8_t fontpage_231_135_135[45] U8G_FONT_SECTION("fontpage_231_135_135") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x88,0x40,0x52,0x80,0x0c, 0x00,0x2a,0x80,0xdf,0x40,0x04,0x00,0xff,0xe0,0x04,0x00,0x04,0x00}; const u8g_fntpgm_uint8_t fontpage_234_168_168[45] U8G_FONT_SECTION("fontpage_234_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x44,0x40,0x44,0x40,0x7f,0xc0,0x44, 0x40,0x44,0x40,0x7f,0xc0,0x44,0x40,0x44,0x40,0x84,0x40,0x84,0xc0}; const u8g_fntpgm_uint8_t fontpage_234_204_204[45] U8G_FONT_SECTION("fontpage_234_204_204") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x44,0x40,0x7f,0xc0,0x44,0x40,0x7f, 0xc0,0x0a,0x00,0x31,0x80,0xd1,0x60,0x11,0x00,0x21,0x00,0x41,0x00}; const u8g_fntpgm_uint8_t fontpage_236_253_253[34] U8G_FONT_SECTION("fontpage_236_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x08,0x0b,0x0b,0x0c,0x02,0xff,0x10,0x20,0xff,0x81,0x81,0xff,0x81,0x81,0x81, 0xff,0x81}; const u8g_fntpgm_uint8_t fontpage_237_132_132[45] U8G_FONT_SECTION("fontpage_237_132_132") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x22,0x00,0x42,0x00,0xf7,0xc0,0x98,0x40,0x90, 0x40,0xf4,0x40,0x92,0x40,0x92,0x40,0x90,0x40,0xf0,0x40,0x91,0x80}; +const u8g_fntpgm_uint8_t fontpage_237_227_227[45] U8G_FONT_SECTION("fontpage_237_227_227") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe3,0xe3,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf9,0x00,0xa1,0x00,0xf9,0xe0,0x8a,0x00,0xfa, + 0x80,0xa0,0x40,0xfc,0x00,0x00,0x00,0x7f,0xc0,0x4a,0x40,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_237_244_244[45] U8G_FONT_SECTION("fontpage_237_244_244") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x04,0x00,0x3f,0x80,0x20, 0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0x20,0x80,0xff,0xe0}; -const u8g_fntpgm_uint8_t fontpage_238_129_129[45] U8G_FONT_SECTION("fontpage_238_129_129") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x81,0x81,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x14,0x80,0x25,0x60,0x46,0x20,0x1f, - 0x80,0x30,0x80,0xdf,0x80,0x10,0x80,0x1f,0x80,0x10,0x80,0x1f,0x80}; const u8g_fntpgm_uint8_t fontpage_238_160_160[45] U8G_FONT_SECTION("fontpage_238_160_160") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x07,0xe0,0xf4,0x20,0x97,0xe0,0xf4,0x80,0x94, 0x80,0x97,0xe0,0xf4,0x80,0x94,0x80,0xf4,0xa0,0x96,0x60,0x04,0x20}; const u8g_fntpgm_uint8_t fontpage_240_141_141[45] U8G_FONT_SECTION("fontpage_240_141_141") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x02,0x00,0xfa,0x00,0x23,0xe0,0x24,0x20,0x79, 0x40,0xc9,0x00,0x49,0x00,0x49,0x00,0x7a,0x80,0x4c,0x40,0x08,0x20}; +const u8g_fntpgm_uint8_t fontpage_241_186_186[45] U8G_FONT_SECTION("fontpage_241_186_186") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0xff,0xe0,0x2a,0x20,0x22,0x80,0x77, + 0xe0,0xd4,0x80,0x5f,0xe0,0x54,0x80,0x77,0xe0,0x54,0x80,0x07,0xe0}; const u8g_fntpgm_uint8_t fontpage_243_251_251[45] U8G_FONT_SECTION("fontpage_243_251_251") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xe3,0xe0,0x24,0x20,0xfa,0x40,0x21, 0x80,0x36,0x80,0x29,0xe0,0x62,0x20,0xa5,0x40,0x20,0x80,0x27,0x00}; const u8g_fntpgm_uint8_t fontpage_244_205_205[45] U8G_FONT_SECTION("fontpage_244_205_205") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xef,0xe0,0x21,0x00,0xff,0xc0,0x21, 0x00,0x2f,0xe0,0x34,0x40,0x6f,0xc0,0xa4,0x40,0x27,0xc0,0x2c,0x60}; const u8g_fntpgm_uint8_t fontpage_245_239_239[45] U8G_FONT_SECTION("fontpage_245_239_239") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xef,0xef,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x81,0x00,0x45,0x20,0xf7,0xe0,0x00,0x00,0xaf, 0xe0,0xa1,0x00,0xaf,0xe0,0x4a,0xa0,0x6a,0xa0,0x8a,0xa0,0x08,0x60}; const u8g_fntpgm_uint8_t fontpage_246_201_201[45] U8G_FONT_SECTION("fontpage_246_201_201") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x7b,0xe0,0x94,0x80,0x7f,0xc0,0x04, 0x00,0xff,0xe0,0x01,0x00,0x7f,0xc0,0x11,0x00,0x09,0x00,0x03,0x00}; const u8g_fntpgm_uint8_t fontpage_247_161_161[45] U8G_FONT_SECTION("fontpage_247_161_161") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa1,0xa1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x3d,0xe0,0x52,0x80,0xff,0xe0,0x80, 0x20,0x3f,0x80,0x20,0x80,0x3f,0xc0,0x20,0x40,0x20,0x40,0x3f,0xc0}; +const u8g_fntpgm_uint8_t fontpage_247_177_177[45] U8G_FONT_SECTION("fontpage_247_177_177") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb1,0xb1,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x3d,0xe0,0x4a,0x80,0x94,0x40,0x7f, + 0xc0,0x12,0x40,0x3b,0xc0,0x56,0x40,0x93,0xc0,0x12,0x40,0x13,0xc0}; const u8g_fntpgm_uint8_t fontpage_249_251_251[45] U8G_FONT_SECTION("fontpage_249_251_251") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, 0x00,0x09,0x0b,0x16,0x0c,0x01,0xff,0x03,0x80,0xfc,0x00,0x11,0x00,0x7e,0x00,0x08, 0x00,0x11,0x00,0xff,0x80,0x08,0x80,0x2a,0x00,0x49,0x00,0x98,0x80}; +const u8g_fntpgm_uint8_t fontpage_250_133_133[45] U8G_FONT_SECTION("fontpage_250_133_133") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xc0,0x41,0x00,0xf1,0x00,0x21, + 0x00,0x51,0x00,0xe9,0x00,0x01,0x00,0x51,0x00,0xa9,0x00,0xaf,0xe0}; +const u8g_fntpgm_uint8_t fontpage_250_162_162[45] U8G_FONT_SECTION("fontpage_250_162_162") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xc0,0x04,0x00,0xff,0xe0,0x91, + 0x20,0x3e,0x00,0x08,0x80,0x7f,0xc0,0x04,0x40,0x24,0x80,0xcc,0x60}; const u8g_fntpgm_uint8_t fontpage_250_171_171[45] U8G_FONT_SECTION("fontpage_250_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x51,0x40,0x5d,0x80,0x51,0x20,0xfd, 0xe0,0x08,0x80,0x3f,0x00,0x08,0x80,0x7f,0xc0,0x24,0x80,0xcc,0x60}; const u8g_fntpgm_uint8_t fontpage_250_176_176[45] U8G_FONT_SECTION("fontpage_250_176_176") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xb0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xe0,0x55,0x20,0xf5,0x20,0x25, 0x20,0x57,0xe0,0xed,0x20,0x05,0x20,0x55,0x20,0xaf,0xe0,0xac,0x20}; const u8g_fntpgm_uint8_t fontpage_250_194_194[45] U8G_FONT_SECTION("fontpage_250_194_194") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc2,0xc2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc2,0xc2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x23,0xc0,0x54,0x40,0xf2,0x80,0x21, 0x00,0x52,0x80,0xec,0x60,0x01,0x00,0x50,0x80,0xab,0x00,0x80,0xc0}; const u8g_fntpgm_uint8_t fontpage_250_241_242[73] U8G_FONT_SECTION("fontpage_250_241_242") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf1,0xf2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x20,0x80,0x57,0xe0,0xf1,0x00,0x22, 0x40,0x57,0xa0,0xe8,0x00,0x02,0x80,0x52,0xa0,0xac,0xa0,0xa8,0x60,0x0b,0x0b,0x16, 0x0c,0x00,0xff,0x21,0x00,0x21,0x00,0x52,0x40,0xf7,0x80,0x21,0x40,0x57,0xe0,0xe8, 0x80,0x02,0xc0,0x54,0xa0,0xa8,0xa0,0xa9,0x80}; +const u8g_fntpgm_uint8_t fontpage_251_160_160[45] U8G_FONT_SECTION("fontpage_251_160_160") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa0,0xa0,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x23,0xc0,0x22,0x40,0x57,0x80,0xf0,0x80,0x2f, + 0xe0,0x51,0x20,0xed,0x40,0x03,0x80,0x55,0x40,0xa9,0x20,0xaf,0x20}; const u8g_fntpgm_uint8_t fontpage_251_178_178[45] U8G_FONT_SECTION("fontpage_251_178_178") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb2,0xb2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb2,0xb2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xe0,0x24,0x20,0x55,0x60,0xf4,0xa0,0x27, 0xe0,0x54,0xa0,0xef,0xe0,0x05,0x20,0x55,0xe0,0xac,0x20,0xac,0x60}; const u8g_fntpgm_uint8_t fontpage_251_210_210[45] U8G_FONT_SECTION("fontpage_251_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x20,0x27,0xa0,0x51,0x40,0xff,0xe0,0x21, 0x00,0x53,0xe0,0xee,0x20,0x03,0xe0,0x52,0x20,0xab,0xe0,0xaa,0x20}; const u8g_fntpgm_uint8_t fontpage_251_218_218[45] U8G_FONT_SECTION("fontpage_251_218_218") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xda,0xda,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xda,0xda,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xc0,0x54,0x40,0xf7,0xc0,0x24, 0x40,0x57,0xc0,0xe9,0x20,0x07,0x40,0x53,0x80,0xad,0x40,0xab,0x20}; const u8g_fntpgm_uint8_t fontpage_251_232_232[45] U8G_FONT_SECTION("fontpage_251_232_232") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x2f,0xe0,0x58,0x20,0xff,0xe0,0x28, 0x00,0x5f,0xe0,0xea,0xa0,0x0f,0xe0,0x5a,0xa0,0xaa,0xa0,0xaa,0x60}; const u8g_fntpgm_uint8_t fontpage_252_174_174[45] U8G_FONT_SECTION("fontpage_252_174_174") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xae,0xae,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xe0,0x44,0x20,0xfb,0xe0,0x24, 0x80,0x5d,0xe0,0xf5,0x20,0x05,0xe0,0x55,0x20,0xad,0xe0,0xa5,0x20}; const u8g_fntpgm_uint8_t fontpage_252_189_189[45] U8G_FONT_SECTION("fontpage_252_189_189") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbd,0xbd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x27,0xe0,0x55,0x60,0xf6,0xa0,0x25, 0x20,0x56,0xa0,0xef,0xe0,0x01,0x40,0x56,0xa0,0xaa,0x60,0xa9,0xc0}; const u8g_fntpgm_uint8_t fontpage_252_252_252[45] U8G_FONT_SECTION("fontpage_252_252_252") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfc,0xfc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfc,0xfc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4a,0x40,0x4d,0xa0,0x8a,0x40,0xfd,0xa0,0x28, 0x00,0x4f,0xe0,0xfa,0x40,0x0d,0xa0,0x5a,0x40,0xad,0xa0,0xaf,0xe0}; const u8g_fntpgm_uint8_t fontpage_253_140_140[45] U8G_FONT_SECTION("fontpage_253_140_140") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8c,0x8c,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x4f,0xe0,0x91,0x00,0xef,0xe0,0x2a, 0xa0,0x5f,0xe0,0xf4,0x40,0x07,0xc0,0x54,0x40,0xaf,0xc0,0xac,0x60}; const u8g_fntpgm_uint8_t fontpage_253_162_162[45] U8G_FONT_SECTION("fontpage_253_162_162") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa2,0xa2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x00,0x27,0xc0,0x41,0x00,0x51,0x00,0xe1, 0x00,0x21,0x00,0x41,0x00,0xf1,0x00,0x01,0x00,0x31,0x00,0xcf,0xe0}; -const u8g_fntpgm_uint8_t fontpage_253_255_255[45] U8G_FONT_SECTION("fontpage_253_255_255") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xff,0xff,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xc0,0x20,0x40,0x43,0xc0,0xf0,0x40,0x2f, - 0xe0,0x41,0x20,0xf5,0x40,0x03,0x80,0x35,0x40,0xc9,0x20,0x03,0x00}; -const u8g_fntpgm_uint8_t fontpage_254_186_186[45] U8G_FONT_SECTION("fontpage_254_186_186") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xba,0xba,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x41,0x00,0x7b,0xc0,0xa1,0x40,0x21, - 0x40,0xff,0xe0,0x21,0x00,0xa9,0x00,0xaa,0x80,0xfa,0x40,0x04,0x20}; -const u8g_fntpgm_uint8_t fontpage_254_209_209[45] U8G_FONT_SECTION("fontpage_254_209_209") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0xff,0x00, - 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x80,0x40,0x91,0x40,0xd5,0x40,0xa2, - 0x40,0x92,0x40,0xad,0x40,0xc5,0x40,0x88,0x40,0x80,0x40,0x81,0xc0}; const u8g_fntpgm_uint8_t fontpage_254_238_238[45] U8G_FONT_SECTION("fontpage_254_238_238") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xee,0xee,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xee,0xee,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x4a,0x40,0x7f,0xc0,0x04,0x00,0xff, 0xe0,0x20,0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_254_242_242[45] U8G_FONT_SECTION("fontpage_254_242_242") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf2,0xf2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xe0,0x49,0x20,0x7f,0xe0,0x04,0x40,0x3f, 0x80,0x05,0x00,0xff,0xe0,0x30,0x80,0xdf,0x80,0x10,0x80,0x1f,0x80}; const u8g_fntpgm_uint8_t fontpage_256_240_240[45] U8G_FONT_SECTION("fontpage_256_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf9,0x00,0x57,0xe0,0x56,0xa0,0x75,0x20,0x56, 0xa0,0x77,0xe0,0x51,0x00,0x52,0xc0,0xfe,0x20,0x12,0x60,0x11,0xc0}; const u8g_fntpgm_uint8_t fontpage_259_234_234[34] U8G_FONT_SECTION("fontpage_259_234_234") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, 0x00,0x07,0x0b,0x0b,0x0c,0x02,0xff,0x20,0xfe,0x82,0x82,0xfe,0x82,0xfe,0x82,0x82, 0xfe,0x82}; -const u8g_fntpgm_uint8_t fontpage_265_221_221[45] U8G_FONT_SECTION("fontpage_265_221_221") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x11,0x00,0x52,0x00,0x53, - 0xc0,0x55,0x00,0x10,0x80,0x7f,0xc0,0x4a,0x40,0x4a,0x40,0xff,0xe0}; +const u8g_fntpgm_uint8_t fontpage_267_205_205[45] U8G_FONT_SECTION("fontpage_267_205_205") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x91,0x00,0xf9,0xe0,0x8a, + 0x80,0xfc,0x40,0x90,0x00,0xff,0xc0,0x4a,0x40,0x4a,0x40,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_272_204_204[45] U8G_FONT_SECTION("fontpage_272_204_204") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xc0,0x40,0x00,0x80,0x00,0x10,0x00,0x2f, 0xe0,0x60,0x80,0xa0,0x80,0x20,0x80,0x20,0x80,0x20,0x80,0x23,0x80}; const u8g_fntpgm_uint8_t fontpage_272_232_232[45] U8G_FONT_SECTION("fontpage_272_232_232") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xc0,0x04,0x00,0x3f,0x80,0x04, 0x00,0xff,0xe0,0x0a,0x40,0x12,0x80,0x31,0x00,0xd4,0x80,0x18,0x60}; const u8g_fntpgm_uint8_t fontpage_273_171_171[45] U8G_FONT_SECTION("fontpage_273_171_171") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xab,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x80,0x20,0x80,0xff,0xe0,0x14,0xa0,0x2c, 0x80,0x77,0xe0,0xad,0x40,0x25,0x40,0x24,0x80,0x29,0x40,0x36,0x20}; const u8g_fntpgm_uint8_t fontpage_273_197_197[45] U8G_FONT_SECTION("fontpage_273_197_197") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x9f,0xe0,0x51,0x00,0x31,0x00,0xd7, 0xc0,0x12,0x00,0xff,0xe0,0x0c,0x40,0x32,0x80,0xd1,0x00,0x18,0xe0}; const u8g_fntpgm_uint8_t fontpage_273_221_221[45] U8G_FONT_SECTION("fontpage_273_221_221") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x51,0x00,0x7f,0xe0,0x11,0x00,0xf1,0x00,0x57, 0xc0,0x84,0x00,0xff,0xe0,0x14,0x80,0x33,0x00,0xd5,0x80,0x18,0x60}; const u8g_fntpgm_uint8_t fontpage_274_135_135[45] U8G_FONT_SECTION("fontpage_274_135_135") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x00,0x27,0xe0,0xf8,0x00,0x17,0xc0,0x2c, 0x40,0x77,0xc0,0xac,0x40,0x27,0xc0,0x2c,0x40,0x33,0x80,0x2c,0x60}; const u8g_fntpgm_uint8_t fontpage_275_210_210[45] U8G_FONT_SECTION("fontpage_275_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x00,0xff,0x10,0x00,0x1f,0x00,0x22,0x00,0x7f,0xc0,0xa4, 0x40,0x3f,0xc0,0x24,0x40,0x3f,0xc0,0x24,0x40,0x45,0x40,0x80,0x80}; const u8g_fntpgm_uint8_t fontpage_276_136_136[45] U8G_FONT_SECTION("fontpage_276_136_136") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x10,0x80,0xfc,0x80,0x00,0x80,0x7f, 0xe0,0x00,0x80,0x78,0x80,0x00,0x80,0x78,0x80,0x48,0x80,0x78,0x80}; const u8g_fntpgm_uint8_t fontpage_276_138_138[45] U8G_FONT_SECTION("fontpage_276_138_138") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xc0,0xf2,0x40,0x02,0x40,0xf2,0x40,0x02, 0x40,0xff,0xc0,0x02,0x40,0xf2,0x40,0x92,0x60,0xf2,0x60,0x92,0x20}; const u8g_fntpgm_uint8_t fontpage_276_152_152[45] U8G_FONT_SECTION("fontpage_276_152_152") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x98,0x98,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x98,0x98,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x00,0xf7,0xc0,0x00,0x40,0xf0,0x40,0x07, 0xc0,0xf4,0x40,0x04,0x00,0xf4,0x00,0x94,0x20,0xf4,0x20,0x93,0xe0}; const u8g_fntpgm_uint8_t fontpage_276_173_173[45] U8G_FONT_SECTION("fontpage_276_173_173") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xad,0xad,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0x80,0xf4,0x80,0x04,0x80,0xf4,0xe0,0x08, 0x00,0xf7,0xc0,0x04,0x40,0xf2,0x80,0x91,0x00,0xf2,0x80,0x9c,0x60}; const u8g_fntpgm_uint8_t fontpage_276_230_230[45] U8G_FONT_SECTION("fontpage_276_230_230") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe6,0xe6,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe6,0xe6,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0xc0,0xf0,0xa0,0x0f,0xe0,0xf0,0x80,0x07, 0x80,0xf2,0x80,0x02,0x80,0xf2,0x80,0x93,0xa0,0xfc,0x60,0x90,0x20}; +const u8g_fntpgm_uint8_t fontpage_277_141_141[45] U8G_FONT_SECTION("fontpage_277_141_141") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8d,0x8d,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xe0,0xf9,0x20,0x05,0x20,0xf5,0x20,0x02, + 0xe0,0xf4,0x40,0x03,0x00,0xf2,0xa0,0x96,0x20,0xfa,0x40,0x91,0xc0}; const u8g_fntpgm_uint8_t fontpage_277_164_164[45] U8G_FONT_SECTION("fontpage_277_164_164") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa4,0xa4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0xf4,0x40,0x04,0x40,0xf7,0xc0,0x00, 0x00,0xf7,0xc0,0x01,0x00,0xff,0xe0,0x92,0x80,0xf4,0x40,0x98,0x20}; const u8g_fntpgm_uint8_t fontpage_277_191_191[45] U8G_FONT_SECTION("fontpage_277_191_191") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xe0,0xf4,0x20,0x05,0x20,0xf7,0xa0,0x05, 0x20,0xf7,0xe0,0x04,0x20,0xf7,0xa0,0x96,0xa0,0xf7,0xa0,0x98,0x60}; const u8g_fntpgm_uint8_t fontpage_277_203_203[45] U8G_FONT_SECTION("fontpage_277_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0xff,0xe0,0x01,0x00,0xf7,0xc0,0x01, 0x00,0xff,0xe0,0x04,0x40,0xf7,0xc0,0x94,0x40,0xf7,0xc0,0x94,0x40}; const u8g_fntpgm_uint8_t fontpage_278_240_240[45] U8G_FONT_SECTION("fontpage_278_240_240") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf0,0xf0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x40,0xff,0xe0,0x01,0x00,0xf7,0xc0,0x01, 0x00,0xff,0xe0,0x04,0xa0,0xff,0xe0,0x94,0xa0,0xfe,0x40,0x95,0xa0}; +const u8g_fntpgm_uint8_t fontpage_279_128_128[45] U8G_FONT_SECTION("fontpage_279_128_128") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0xff,0xe0,0x01,0x00,0xff,0xe0,0x0a, + 0xa0,0xff,0xe0,0x04,0x40,0xf7,0xc0,0x94,0x40,0xf7,0xc0,0x9c,0x60}; const u8g_fntpgm_uint8_t fontpage_279_138_138[45] U8G_FONT_SECTION("fontpage_279_138_138") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x40,0xae,0xa0,0x40,0x40,0xae,0xa0,0xea, 0xe0,0x5e,0x40,0xa0,0xa0,0x1f,0xc0,0x69,0x00,0x06,0x00,0x79,0xe0}; const u8g_fntpgm_uint8_t fontpage_281_199_199[45] U8G_FONT_SECTION("fontpage_281_199_199") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc7,0xc7,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x88,0x00,0x5f,0xc0,0x22,0x40,0xff,0x00,0x61, 0xc0,0x3f,0x00,0x21,0x00,0x3f,0x00,0x21,0x00,0x3f,0x00,0xe1,0xc0}; +const u8g_fntpgm_uint8_t fontpage_283_221_221[45] U8G_FONT_SECTION("fontpage_283_221_221") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7b,0xe0,0x4a,0x00,0x4a,0x00,0x7b,0xe0,0x12, + 0x20,0x52,0x20,0x5a,0x20,0x53,0xe0,0x52,0x00,0x5e,0x00,0xe3,0xe0}; +const u8g_fntpgm_uint8_t fontpage_285_202_202[45] U8G_FONT_SECTION("fontpage_285_202_202") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xc0,0x04,0x00,0x3f,0x80,0x24, + 0x80,0x3f,0x80,0x24,0x80,0x3f,0x80,0x04,0x00,0xff,0xe0,0x04,0x00}; +const u8g_fntpgm_uint8_t fontpage_285_223_223[45] U8G_FONT_SECTION("fontpage_285_223_223") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdf,0xdf,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0xfa,0x00,0x23,0xe0,0xfd,0x20,0xa9, + 0x40,0xf9,0x00,0xa9,0x00,0xf9,0x80,0x22,0x80,0xfa,0x40,0x24,0x20}; const u8g_fntpgm_uint8_t fontpage_285_248_248[45] U8G_FONT_SECTION("fontpage_285_248_248") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0xf8,0x80,0x23,0xe0,0xfa,0xa0,0xaa, 0xa0,0xfa,0xa0,0xab,0xe0,0xfa,0xa0,0x22,0xa0,0xfb,0xe0,0x22,0x20}; const u8g_fntpgm_uint8_t fontpage_286_137_137[45] U8G_FONT_SECTION("fontpage_286_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x80,0x7d,0x40,0x11,0x00,0xff,0xe0,0x11, 0x00,0xff,0x20,0x55,0x40,0x7c,0x80,0x54,0xa0,0xff,0x60,0x12,0x20}; const u8g_fntpgm_uint8_t fontpage_286_175_175[45] U8G_FONT_SECTION("fontpage_286_175_175") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x23,0xc0,0xfa,0x40,0x23,0xc0,0xf8,0x00,0xaf, 0xe0,0xfa,0x40,0xab,0xc0,0xfa,0x40,0x22,0xe0,0xff,0x40,0x20,0x40}; const u8g_fntpgm_uint8_t fontpage_286_184_184[45] U8G_FONT_SECTION("fontpage_286_184_184") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb8,0xb8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb8,0xb8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0xfa,0x80,0x24,0x60,0xfb,0x80,0xae, 0x20,0xfa,0xa0,0xae,0xa0,0xfa,0xa0,0x2e,0xa0,0xfa,0x20,0x2a,0x60}; +const u8g_fntpgm_uint8_t fontpage_286_201_201[45] U8G_FONT_SECTION("fontpage_286_201_201") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc9,0xc9,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0xff,0xe0,0x25,0x40,0xff,0xc0,0xad, + 0x40,0xff,0xc0,0xa9,0x60,0xff,0xe0,0x24,0x40,0xfa,0x40,0x20,0xc0}; const u8g_fntpgm_uint8_t fontpage_287_209_209[45] U8G_FONT_SECTION("fontpage_287_209_209") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0xc0,0x27,0x00,0x24,0x00,0x07,0xe0,0xe4, 0x80,0x24,0x80,0x24,0x80,0x24,0x80,0x28,0x80,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_287_212_212[45] U8G_FONT_SECTION("fontpage_287_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0x60,0x27,0x80,0x24,0x00,0x07,0xe0,0xe6, 0x20,0x25,0x40,0x24,0x80,0x29,0x40,0x26,0x20,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_128_128[45] U8G_FONT_SECTION("fontpage_288_128_128") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x8f,0xc0,0x48,0x40,0x4f,0xc0,0x08,0x40,0xcf, 0xc0,0x48,0x00,0x4b,0x40,0x48,0x80,0x4e,0x40,0xb0,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_159_159[45] U8G_FONT_SECTION("fontpage_288_159_159") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9f,0x9f,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x3f,0xe0,0x21,0x00,0x0f,0xe0,0xe9, 0x20,0x2f,0xe0,0x23,0x80,0x25,0x40,0x29,0x20,0x51,0x00,0x8f,0xe0}; +const u8g_fntpgm_uint8_t fontpage_288_163_163[45] U8G_FONT_SECTION("fontpage_288_163_163") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa3,0xa3,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x2f,0xe0,0x25,0x40,0x07,0xc0,0xe5, + 0x40,0x27,0xc0,0x21,0x00,0x2f,0xe0,0x21,0x00,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_178_178[45] U8G_FONT_SECTION("fontpage_288_178_178") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb2,0xb2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb2,0xb2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x43,0x00,0x24,0x80,0x27,0xe0,0x0c,0x80,0xf7, 0xe0,0x24,0x80,0x27,0xe0,0x24,0x80,0x27,0xe0,0x54,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_203_203[45] U8G_FONT_SECTION("fontpage_288_203_203") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xe0,0x29,0x20,0x2f,0xe0,0x05,0x40,0xe7, 0xc0,0x25,0x40,0x27,0xc0,0x21,0x00,0x2f,0xe0,0x51,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_212_212[45] U8G_FONT_SECTION("fontpage_288_212_212") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x27,0xc0,0x21,0x00,0x0f,0xe0,0xe2, 0x80,0x2f,0xe0,0x21,0x00,0x2f,0xe0,0x21,0x00,0x51,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_288_248_248[45] U8G_FONT_SECTION("fontpage_288_248_248") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf8,0xf8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4e,0xe0,0x2a,0xa0,0x2e,0xe0,0x08,0x80,0xea, 0xa0,0x2f,0xe0,0x22,0x80,0x2f,0xe0,0x22,0x40,0x54,0x20,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_289_132_132[45] U8G_FONT_SECTION("fontpage_289_132_132") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x9f,0xc0,0x55,0x40,0x5f,0xc0,0x00,0x00,0xff, 0xe0,0x28,0x80,0x2f,0xa0,0x27,0x40,0x2a,0x80,0x52,0x40,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_289_138_138[45] U8G_FONT_SECTION("fontpage_289_138_138") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8a,0x8a,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x42,0x00,0x2f,0xc0,0x28,0x40,0x1f,0xe0,0xf4, 0xa0,0x29,0x40,0x3f,0xe0,0x22,0x00,0x27,0xc0,0x58,0xc0,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_289_232_232[45] U8G_FONT_SECTION("fontpage_289_232_232") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0xe0,0xff,0x20,0x45,0x20,0x29,0x40,0xff, 0x80,0x01,0x40,0x7d,0x20,0x45,0x20,0x45,0xa0,0x7d,0x40,0x45,0x00}; -const u8g_fntpgm_uint8_t fontpage_291_202_202[45] U8G_FONT_SECTION("fontpage_291_202_202") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x1f,0xc0,0xe2,0x80,0xa9,0x00,0x72,0x80,0xfd, - 0x60,0x31,0x00,0x6f,0xc0,0xa1,0x00,0xaf,0xe0,0x21,0x00,0x21,0x00}; +const u8g_fntpgm_uint8_t fontpage_291_203_203[45] U8G_FONT_SECTION("fontpage_291_203_203") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcb,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x2a,0xa0,0xaf,0xe0,0x71,0x00,0xff, + 0xe0,0x22,0x80,0x77,0xe0,0x69,0x00,0xa7,0xe0,0xa1,0x00,0x21,0x00}; const u8g_fntpgm_uint8_t fontpage_291_205_205[45] U8G_FONT_SECTION("fontpage_291_205_205") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0xff,0xe0,0x24,0x80,0x3f, 0x80,0x24,0x80,0x3f,0x80,0x04,0x00,0x7f,0xc0,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_291_207_207[45] U8G_FONT_SECTION("fontpage_291_207_207") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcf,0xcf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0x80,0x20,0x80,0x3f,0x80,0x20,0x80,0xff, 0xe0,0x24,0x80,0x3f,0x80,0x24,0x80,0x7f,0xc0,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_291_221_221[45] U8G_FONT_SECTION("fontpage_291_221_221") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdd,0xdd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x20,0x80,0x50,0x80,0x88,0x80,0x78,0x80,0x27, 0xe0,0xf8,0x80,0x20,0x80,0xa8,0x80,0x70,0x80,0x38,0x80,0xc0,0x80}; const u8g_fntpgm_uint8_t fontpage_292_149_149[45] U8G_FONT_SECTION("fontpage_292_149_149") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x95,0x95,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x95,0x95,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x27,0xc0,0x31,0x40,0x49,0x40,0xf9,0x40,0x21, 0x40,0xff,0xc0,0x22,0x40,0xaa,0x40,0x72,0x40,0x3a,0x40,0xc7,0xe0}; const u8g_fntpgm_uint8_t fontpage_294_175_175[45] U8G_FONT_SECTION("fontpage_294_175_175") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xaf,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x40,0x57,0xe0,0x8a,0x40,0x7a,0x40,0x27, 0xe0,0xf8,0x00,0x23,0xe0,0xaa,0x20,0x73,0xe0,0x3a,0x20,0xe3,0xe0}; const u8g_fntpgm_uint8_t fontpage_294_245_245[45] U8G_FONT_SECTION("fontpage_294_245_245") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf5,0xf5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf5,0xf5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2c,0x80,0x25,0xe0,0x54,0xa0,0xfb,0xe0,0x2c, 0xa0,0xf7,0xe0,0x24,0x80,0xb7,0xe0,0x6c,0x80,0x34,0x80,0xcb,0xe0}; const u8g_fntpgm_uint8_t fontpage_298_247_247[45] U8G_FONT_SECTION("fontpage_298_247_247") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf7,0xf7,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0x3f,0x80,0x20,0x00,0x3f,0x00,0x20,0x00,0x3f, 0x00,0x20,0x00,0xff,0xc0,0x24,0x80,0x23,0x00,0x29,0x00,0x30,0xc0}; const u8g_fntpgm_uint8_t fontpage_299_137_137[45] U8G_FONT_SECTION("fontpage_299_137_137") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x89,0x89,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfb,0xe0,0x8a,0x20,0xfb,0xe0,0x8a,0x20,0xfb, 0xe0,0x82,0x20,0xbf,0xa0,0x8a,0x20,0x92,0x20,0xa2,0x20,0x86,0xe0}; const u8g_fntpgm_uint8_t fontpage_299_139_139[45] U8G_FONT_SECTION("fontpage_299_139_139") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8b,0x8b,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfb,0xe0,0x8a,0x20,0xfb,0xe0,0x8a,0x20,0xfb, 0xe0,0x80,0x20,0x9f,0x20,0x8a,0x20,0xbf,0xa0,0x8a,0x20,0x92,0xe0}; const u8g_fntpgm_uint8_t fontpage_299_147_147[45] U8G_FONT_SECTION("fontpage_299_147_147") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x93,0x93,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x93,0x93,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfb,0xe0,0x8a,0x20,0xfb,0xe0,0x8a,0x20,0xfb, 0xe0,0x9f,0x20,0x91,0x20,0x9f,0x20,0x91,0x20,0x9f,0x20,0x80,0xe0}; const u8g_fntpgm_uint8_t fontpage_299_220_220[45] U8G_FONT_SECTION("fontpage_299_220_220") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfb,0xe0,0x8a,0x20,0xfb,0xe0,0x8a,0x20,0xf5, 0xe0,0xaa,0xa0,0xbb,0xa0,0xaa,0xa0,0xbb,0xa0,0x8a,0x20,0xb2,0x60}; const u8g_fntpgm_uint8_t fontpage_300_205_205[45] U8G_FONT_SECTION("fontpage_300_205_205") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf2,0x00,0x93,0xe0,0xa6,0x40,0xc1,0x80,0xa6, 0x60,0x91,0x00,0x97,0xe0,0xd5,0x00,0xaf,0xe0,0x81,0x00,0x81,0x00}; const u8g_fntpgm_uint8_t fontpage_300_228_228[45] U8G_FONT_SECTION("fontpage_300_228_228") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf1,0x00,0x92,0x80,0xa4,0x40,0xcb,0xa0,0xa1, 0x00,0x9f,0xe0,0x91,0x00,0xe5,0x40,0x89,0x20,0x91,0x20,0x83,0x00}; +const u8g_fntpgm_uint8_t fontpage_301_142_142[45] U8G_FONT_SECTION("fontpage_301_142_142") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8e,0x8e,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf8,0x80,0x98,0xa0,0xae,0xc0,0xc8,0xa0,0xae, + 0xe0,0x92,0x00,0x97,0xc0,0xf4,0x40,0xa7,0xc0,0x84,0x40,0x87,0xc0}; const u8g_fntpgm_uint8_t fontpage_301_217_217[45] U8G_FONT_SECTION("fontpage_301_217_217") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd9,0xd9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x2a,0x80,0x3f,0xe0,0x6a,0x80,0xbf,0xc0,0x2a, 0x80,0x3f,0xe0,0x00,0x00,0x3f,0xc0,0x08,0x80,0x07,0x00,0x78,0xe0}; +const u8g_fntpgm_uint8_t fontpage_301_226_226[45] U8G_FONT_SECTION("fontpage_301_226_226") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x80,0xfd,0x40,0x55,0xe0,0x6f,0x40,0x55, + 0xe0,0x7d,0x40,0x21,0x40,0xfd,0xe0,0xad,0x40,0xb5,0x40,0x8d,0xe0}; const u8g_fntpgm_uint8_t fontpage_301_251_251[45] U8G_FONT_SECTION("fontpage_301_251_251") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfb,0xfb,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x04,0x00,0xff,0xe0,0xa4,0xa0,0x7f, 0xc0,0x44,0x40,0x7f,0xc0,0x44,0x40,0x7f,0xc0,0x04,0x20,0x07,0xe0}; const u8g_fntpgm_uint8_t fontpage_302_210_210[45] U8G_FONT_SECTION("fontpage_302_210_210") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd2,0xd2,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0x7f,0xc0,0x04,0x00,0x3f,0x80,0x04, 0x00,0xff,0xe0,0x10,0x80,0x1f,0x80,0x10,0x80,0x1f,0x80,0x10,0x80}; const u8g_fntpgm_uint8_t fontpage_302_222_222[45] U8G_FONT_SECTION("fontpage_302_222_222") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x0a,0x00,0x0a,0x00,0xfb,0xe0,0x0a,0x00,0x0a, 0x00,0x7b,0xc0,0x0a,0x00,0x0a,0x00,0xfb,0xe0,0x0a,0x00,0x0a,0x00}; const u8g_fntpgm_uint8_t fontpage_302_226_226[45] U8G_FONT_SECTION("fontpage_302_226_226") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe2,0xe2,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x08,0x00,0x10,0x00,0xff,0xc0,0x92, 0x40,0x9e,0x40,0x92,0x40,0x9e,0x40,0x92,0x40,0xff,0xc0,0x80,0x40}; const u8g_fntpgm_uint8_t fontpage_304_133_133[45] U8G_FONT_SECTION("fontpage_304_133_133") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x85,0x85,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x07,0xe0,0xf9,0x00,0x27,0xe0,0x24,0x20,0x27, 0xe0,0x24,0x20,0x3f,0xe0,0xc4,0x20,0x07,0xe0,0x02,0x40,0x0c,0x20}; const u8g_fntpgm_uint8_t fontpage_304_144_144[45] U8G_FONT_SECTION("fontpage_304_144_144") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x90,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xff,0xe0,0x91,0x00,0x67,0xc0,0x24,0x40,0xff, 0xc0,0x24,0x40,0x27,0xc0,0x24,0x40,0x27,0xc0,0x22,0x80,0xec,0x60}; const u8g_fntpgm_uint8_t fontpage_304_205_205[45] U8G_FONT_SECTION("fontpage_304_205_205") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x23,0xe0,0xfc,0x80,0xa7,0xe0,0x3a,0x20,0x4b, 0xe0,0xb2,0x20,0x4b,0xe0,0xfe,0x20,0x4b,0xe0,0x79,0x40,0x4e,0x20}; const u8g_fntpgm_uint8_t fontpage_304_222_222[45] U8G_FONT_SECTION("fontpage_304_222_222") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xab,0xe0,0x70,0x80,0x23,0xe0,0xfa,0x20,0x73, 0xe0,0xaa,0x20,0x23,0xe0,0xfa,0x20,0x23,0xe0,0x51,0x40,0x8e,0x20}; -const u8g_fntpgm_uint8_t fontpage_305_132_132[45] U8G_FONT_SECTION("fontpage_305_132_132") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x84,0x84,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xfb,0xe0,0x10,0x80,0x63,0xe0,0x22,0x20,0xfa, - 0xa0,0x2a,0xa0,0x22,0xa0,0x22,0xa0,0x22,0xa0,0x21,0x40,0x66,0x20}; const u8g_fntpgm_uint8_t fontpage_305_168_168[45] U8G_FONT_SECTION("fontpage_305_168_168") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0xc0,0x21,0x40,0x2e,0x40,0x24,0x40,0x3f, 0x40,0x35,0x40,0x3f,0x40,0x25,0x40,0x27,0x60,0x5c,0xa0,0x88,0x20}; const u8g_fntpgm_uint8_t fontpage_305_253_253[45] U8G_FONT_SECTION("fontpage_305_253_253") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xfd,0xfd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x22,0x00,0x52,0x00,0xab,0xe0,0xfc,0x20,0x8b, 0xa0,0xfa,0xa0,0x8b,0xa0,0xfa,0x40,0x92,0x20,0xaa,0x20,0xc9,0xe0}; +const u8g_fntpgm_uint8_t fontpage_306_152_152[45] U8G_FONT_SECTION("fontpage_306_152_152") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x98,0x98,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x21,0x00,0x52,0x80,0xac,0x40,0xf8,0x20,0x8f, + 0xc0,0xf9,0x00,0x8f,0xe0,0xf9,0x00,0x95,0x40,0xb9,0x20,0xcb,0x00}; const u8g_fntpgm_uint8_t fontpage_307_172_172[45] U8G_FONT_SECTION("fontpage_307_172_172") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x3f,0xc0,0x24,0x00,0x3f,0x80,0x24,0x00,0x3f, 0x80,0x24,0x00,0x3f,0xe0,0x00,0x20,0x55,0x20,0x4a,0xa0,0x8a,0xc0}; const u8g_fntpgm_uint8_t fontpage_308_197_197[45] U8G_FONT_SECTION("fontpage_308_197_197") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc5,0xc5,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xe0,0x54,0x00,0x7d,0xc0,0x55,0x40,0x7d, 0xc0,0x54,0x00,0x7f,0xe0,0x5e,0xa0,0xaf,0xe0,0xac,0x00,0x17,0xe0}; +const u8g_fntpgm_uint8_t fontpage_309_212_212[45] U8G_FONT_SECTION("fontpage_309_212_212") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x79,0x40,0x6b,0xe0,0x5a,0xa0,0xff,0xe0,0x86, + 0xa0,0x7f,0xe0,0x4a,0x40,0x7b,0xc0,0x4a,0x40,0x79,0x80,0x4f,0xe0}; const u8g_fntpgm_uint8_t fontpage_309_216_216[45] U8G_FONT_SECTION("fontpage_309_216_216") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd8,0xd8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x00,0x00,0x1f,0x00,0x11, 0x00,0x7f,0xc0,0x40,0x40,0x5f,0x40,0x51,0x40,0x5f,0x40,0x40,0xc0}; -const u8g_fntpgm_uint8_t fontpage_317_196_196[45] U8G_FONT_SECTION("fontpage_317_196_196") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc4,0xc4,0x00,0x0a,0xff,0x00, - 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0x7f,0xc0,0x11,0x00,0xff,0xe0,0x04, - 0x00,0x3f,0x80,0x24,0x80,0x3f,0x80,0x24,0x80,0x3f,0x80,0x60,0xc0}; +const u8g_fntpgm_uint8_t fontpage_317_195_195[45] U8G_FONT_SECTION("fontpage_317_195_195") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc3,0xc3,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x11,0x00,0x1f,0x00,0x00, + 0x00,0xff,0xe0,0x24,0x80,0x3f,0x80,0x24,0x80,0x3f,0x80,0xc0,0x60}; const u8g_fntpgm_uint8_t fontpage_317_222_222[45] U8G_FONT_SECTION("fontpage_317_222_222") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf8,0x80,0xa8,0x80,0xf8,0xe0,0xa8,0x80,0xf8, 0x80,0x23,0xe0,0xfa,0x20,0x22,0x20,0xfa,0x20,0x52,0x20,0xab,0xe0}; +const u8g_fntpgm_uint8_t fontpage_318_202_202[45] U8G_FONT_SECTION("fontpage_318_202_202") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xca,0xca,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x04,0x00,0xff,0xe0,0x0a,0x40,0xf5,0x80,0x55, + 0x40,0x95,0xa0,0x20,0x80,0x3f,0x80,0x20,0x80,0x3f,0x80,0xc0,0x80}; const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510_154_154") = { - 0x00,0x06,0x0c,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x08,0x00,0x00, + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0x9a,0x00,0x08,0x00,0x00, 0x00,0x02,0x07,0x07,0x0c,0x06,0x01,0xc0,0xc0,0x00,0x00,0x00,0xc0,0xc0}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' + FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' FONTDATA_ITEM(156, 166, 166, fontpage_156_166_166), // '並' -- '並' - FONTDATA_ITEM(156, 170, 170, fontpage_156_170_170), // '个' -- '个' FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' FONTDATA_ITEM(156, 187, 187, fontpage_156_187_187), // '主' -- '主' FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' + FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' FONTDATA_ITEM(157, 228, 228, fontpage_157_228_228), // '令' -- '令' + FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' - FONTDATA_ITEM(159, 134, 134, fontpage_159_134_134), // '來' -- '來' FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' @@ -1117,15 +1242,18 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' + FONTDATA_ITEM(160, 245, 245, fontpage_160_245_245), // '偵' -- '偵' FONTDATA_ITEM(161, 153, 153, fontpage_161_153_153), // '備' -- '備' FONTDATA_ITEM(161, 179, 179, fontpage_161_179_179), // '傳' -- '傳' + FONTDATA_ITEM(161, 190, 190, fontpage_161_190_190), // '傾' -- '傾' FONTDATA_ITEM(162, 178, 178, fontpage_162_178_178), // '儲' -- '儲' FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' - FONTDATA_ITEM(162, 200, 200, fontpage_162_200_200), // '先' -- '先' + FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' + FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' FONTDATA_ITEM(163, 250, 250, fontpage_163_250_250), // '出' -- '出' @@ -1137,7 +1265,6 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(164, 245, 245, fontpage_164_245_245), // '創' -- '創' FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' FONTDATA_ITEM(165, 160, 160, fontpage_165_160_160), // '加' -- '加' - FONTDATA_ITEM(165, 168, 168, fontpage_165_168_168), // '动' -- '动' FONTDATA_ITEM(165, 213, 213, fontpage_165_213_213), // '動' -- '動' FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' @@ -1145,30 +1272,39 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' FONTDATA_ITEM(166, 240, 240, fontpage_166_240_240), // '印' -- '印' FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' + FONTDATA_ITEM(166, 251, 251, fontpage_166_251_251), // '卻' -- '卻' FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' + FONTDATA_ITEM(167, 205, 205, fontpage_167_205_205), // '反' -- '反' FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' + FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' + FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' FONTDATA_ITEM(170, 223, 223, fontpage_170_223_223), // '啟' -- '啟' FONTDATA_ITEM(171, 174, 174, fontpage_171_174_174), // '單' -- '單' FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' + FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' + FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' FONTDATA_ITEM(174, 150, 150, fontpage_174_150_150), // '圖' -- '圖' FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' + FONTDATA_ITEM(175, 247, 247, fontpage_175_247_247), // '執' -- '執' FONTDATA_ITEM(176, 202, 202, fontpage_176_202_202), // '塊' -- '塊' FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' FONTDATA_ITEM(177, 138, 138, fontpage_177_138_138), // '墊' -- '墊' FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' + FONTDATA_ITEM(178, 160, 160, fontpage_178_160_160), // '夠' -- '夠' FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' + FONTDATA_ITEM(181, 146, 146, fontpage_181_146_146), // '媒' -- '媒' FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' @@ -1180,12 +1316,14 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' + FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' FONTDATA_ITEM(189, 226, 226, fontpage_189_226_226), // '廢' -- '廢' FONTDATA_ITEM(189, 250, 250, fontpage_189_250_250), // '建' -- '建' + FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' FONTDATA_ITEM(191, 133, 133, fontpage_191_133_133), // '待' -- '待' FONTDATA_ITEM(191, 140, 140, fontpage_191_140_140), // '後' -- '後' FONTDATA_ITEM(191, 145, 145, fontpage_191_145_145), // '徑' -- '徑' @@ -1204,7 +1342,6 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' - FONTDATA_ITEM(196, 231, 231, fontpage_196_231_231), // '执' -- '执' FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' @@ -1212,12 +1349,15 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' + FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' + FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' FONTDATA_ITEM(199, 219, 219, fontpage_199_219_219), // '換' -- '換' FONTDATA_ITEM(201, 199, 199, fontpage_201_199_199), // '擇' -- '擇' FONTDATA_ITEM(201, 202, 203, fontpage_201_202_203), // '擊' -- '擋' FONTDATA_ITEM(201, 224, 224, fontpage_201_224_224), // '擠' -- '擠' + FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' FONTDATA_ITEM(202, 215, 215, fontpage_202_215_215), // '敗' -- '敗' FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' @@ -1225,8 +1365,11 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' + FONTDATA_ITEM(203, 183, 183, fontpage_203_183_183), // '斷' -- '斷' FONTDATA_ITEM(203, 188, 188, fontpage_203_188_188), // '於' -- '於' + FONTDATA_ITEM(204, 135, 135, fontpage_204_135_135), // '昇' -- '昇' FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' + FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' FONTDATA_ITEM(204, 194, 194, fontpage_204_194_194), // '時' -- '時' FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' @@ -1237,19 +1380,18 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' FONTDATA_ITEM(209, 157, 157, fontpage_209_157_157), // '條' -- '條' + FONTDATA_ITEM(209, 196, 196, fontpage_209_196_196), // '棄' -- '棄' FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' FONTDATA_ITEM(212, 223, 223, fontpage_212_223_223), // '機' -- '機' FONTDATA_ITEM(213, 162, 162, fontpage_213_162_162), // '檢' -- '檢' - FONTDATA_ITEM(214, 226, 226, fontpage_214_226_226), // '止' -- '止' + FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' FONTDATA_ITEM(214, 248, 248, fontpage_214_248_248), // '歸' -- '歸' FONTDATA_ITEM(215, 188, 188, fontpage_215_188_188), // '殼' -- '殼' FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' FONTDATA_ITEM(217, 146, 146, fontpage_217_146_146), // '沒' -- '沒' - FONTDATA_ITEM(218, 187, 187, fontpage_218_187_187), // '活' -- '活' FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' - FONTDATA_ITEM(219, 188, 188, fontpage_219_188_188), // '涼' -- '涼' FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' FONTDATA_ITEM(220, 172, 172, fontpage_220_172_172), // '測' -- '測' @@ -1257,30 +1399,35 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(221, 150, 150, fontpage_221_150_150), // '準' -- '準' FONTDATA_ITEM(221, 171, 171, fontpage_221_171_171), // '溫' -- '溫' FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' - FONTDATA_ITEM(224, 239, 239, fontpage_224_239_239), // '灯' -- '灯' FONTDATA_ITEM(226, 161, 161, fontpage_226_161_161), // '無' -- '無' FONTDATA_ITEM(227, 177, 177, fontpage_227_177_177), // '熱' -- '熱' FONTDATA_ITEM(227, 200, 200, fontpage_227_200_200), // '燈' -- '燈' FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' + FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' FONTDATA_ITEM(234, 204, 204, fontpage_234_204_204), // '界' -- '界' FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' + FONTDATA_ITEM(237, 227, 227, fontpage_237_227_227), // '監' -- '監' FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' - FONTDATA_ITEM(238, 129, 129, fontpage_238_129_129), // '省' -- '省' FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' FONTDATA_ITEM(240, 141, 141, fontpage_240_141_141), // '砍' -- '砍' + FONTDATA_ITEM(241, 186, 186, fontpage_241_186_186), // '確' -- '確' FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' FONTDATA_ITEM(244, 205, 205, fontpage_244_205_205), // '積' -- '積' FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' FONTDATA_ITEM(247, 161, 161, fontpage_247_161_161), // '管' -- '管' + FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' FONTDATA_ITEM(249, 251, 251, fontpage_249_251_251), // '系' -- '系' + FONTDATA_ITEM(250, 133, 133, fontpage_250_133_133), // '紅' -- '紅' + FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' FONTDATA_ITEM(250, 176, 176, fontpage_250_176_176), // '細' -- '細' FONTDATA_ITEM(250, 194, 194, fontpage_250_194_194), // '終' -- '終' FONTDATA_ITEM(250, 241, 242, fontpage_250_241_242), // '統' -- '絲' + FONTDATA_ITEM(251, 160, 160, fontpage_251_160_160), // '綠' -- '綠' FONTDATA_ITEM(251, 178, 178, fontpage_251_178_178), // '網' -- '網' FONTDATA_ITEM(251, 210, 210, fontpage_251_210_210), // '緒' -- '緒' FONTDATA_ITEM(251, 218, 218, fontpage_251_218_218), // '線' -- '線' @@ -1290,14 +1437,11 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(252, 252, 252, fontpage_252_252_252), // '繼' -- '繼' FONTDATA_ITEM(253, 140, 140, fontpage_253_140_140), // '續' -- '續' FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' - FONTDATA_ITEM(253, 255, 255, fontpage_253_255_255), // '绿' -- '绿' - FONTDATA_ITEM(254, 186, 186, fontpage_254_186_186), // '缺' -- '缺' - FONTDATA_ITEM(254, 209, 209, fontpage_254_209_209), // '网' -- '网' FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' FONTDATA_ITEM(256, 240, 240, fontpage_256_240_240), // '聰' -- '聰' FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' - FONTDATA_ITEM(265, 221, 221, fontpage_265_221_221), // '蓝' -- '蓝' + FONTDATA_ITEM(267, 205, 205, fontpage_267_205_205), // '藍' -- '藍' FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' FONTDATA_ITEM(272, 232, 232, fontpage_272_232_232), // '表' -- '表' FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' @@ -1310,20 +1454,27 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(276, 152, 152, fontpage_276_152_152), // '記' -- '記' FONTDATA_ITEM(276, 173, 173, fontpage_276_173_173), // '設' -- '設' FONTDATA_ITEM(276, 230, 230, fontpage_276_230_230), // '試' -- '試' + FONTDATA_ITEM(277, 141, 141, fontpage_277_141_141), // '認' -- '認' FONTDATA_ITEM(277, 164, 164, fontpage_277_164_164), // '誤' -- '誤' FONTDATA_ITEM(277, 191, 191, fontpage_277_191_191), // '調' -- '調' FONTDATA_ITEM(277, 203, 203, fontpage_277_203_203), // '請' -- '請' FONTDATA_ITEM(278, 240, 240, fontpage_278_240_240), // '議' -- '議' + FONTDATA_ITEM(279, 128, 128, fontpage_279_128_128), // '讀' -- '讀' FONTDATA_ITEM(279, 138, 138, fontpage_279_138_138), // '變' -- '變' FONTDATA_ITEM(281, 199, 199, fontpage_281_199_199), // '資' -- '資' + FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' + FONTDATA_ITEM(285, 202, 202, fontpage_285_202_202), // '車' -- '車' + FONTDATA_ITEM(285, 223, 223, fontpage_285_223_223), // '軟' -- '軟' FONTDATA_ITEM(285, 248, 248, fontpage_285_248_248), // '軸' -- '軸' FONTDATA_ITEM(286, 137, 137, fontpage_286_137_137), // '載' -- '載' FONTDATA_ITEM(286, 175, 175, fontpage_286_175_175), // '輯' -- '輯' FONTDATA_ITEM(286, 184, 184, fontpage_286_184_184), // '輸' -- '輸' + FONTDATA_ITEM(286, 201, 201, fontpage_286_201_201), // '轉' -- '轉' FONTDATA_ITEM(287, 209, 209, fontpage_287_209_209), // '近' -- '近' FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' + FONTDATA_ITEM(288, 163, 163, fontpage_288_163_163), // '連' -- '連' FONTDATA_ITEM(288, 178, 178, fontpage_288_178_178), // '進' -- '進' FONTDATA_ITEM(288, 203, 203, fontpage_288_203_203), // '運' -- '運' FONTDATA_ITEM(288, 212, 212, fontpage_288_212_212), // '達' -- '達' @@ -1331,7 +1482,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(289, 132, 132, fontpage_289_132_132), // '還' -- '還' FONTDATA_ITEM(289, 138, 138, fontpage_289_138_138), // '邊' -- '邊' FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' - FONTDATA_ITEM(291, 202, 202, fontpage_291_202_202), // '释' -- '释' + FONTDATA_ITEM(291, 203, 203, fontpage_291_203_203), // '釋' -- '釋' FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' FONTDATA_ITEM(291, 221, 221, fontpage_291_221_221), // '針' -- '針' @@ -1345,7 +1496,9 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(299, 220, 220, fontpage_299_220_220), // '關' -- '關' FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' + FONTDATA_ITEM(301, 142, 142, fontpage_301_142_142), // '階' -- '階' FONTDATA_ITEM(301, 217, 217, fontpage_301_217_217), // '雙' -- '雙' + FONTDATA_ITEM(301, 226, 226, fontpage_301_226_226), // '離' -- '離' FONTDATA_ITEM(301, 251, 251, fontpage_301_251_251), // '電' -- '電' FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' @@ -1354,13 +1507,15 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(304, 144, 144, fontpage_304_144_144), // '預' -- '預' FONTDATA_ITEM(304, 205, 205, fontpage_304_205_205), // '額' -- '額' FONTDATA_ITEM(304, 222, 222, fontpage_304_222_222), // '類' -- '類' - FONTDATA_ITEM(305, 132, 132, fontpage_305_132_132), // '预' -- '预' FONTDATA_ITEM(305, 168, 168, fontpage_305_168_168), // '風' -- '風' FONTDATA_ITEM(305, 253, 253, fontpage_305_253_253), // '飽' -- '飽' + FONTDATA_ITEM(306, 152, 152, fontpage_306_152_152), // '餘' -- '餘' FONTDATA_ITEM(307, 172, 172, fontpage_307_172_172), // '馬' -- '馬' FONTDATA_ITEM(308, 197, 197, fontpage_308_197_197), // '驅' -- '驅' + FONTDATA_ITEM(309, 212, 212, fontpage_309_212_212), // '體' -- '體' FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' - FONTDATA_ITEM(317, 196, 196, fontpage_317_196_196), // '黄' -- '黄' + FONTDATA_ITEM(317, 195, 195, fontpage_317_195_195), // '黃' -- '黃' FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' + FONTDATA_ITEM(318, 202, 202, fontpage_318_202_202), // '齊' -- '齊' FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' }; From 27f0f105908e73d91f89964b49fa9d7afac4ae1a Mon Sep 17 00:00:00 2001 From: RudolphRiedel <31180093+RudolphRiedel@users.noreply.github.com> Date: Mon, 20 Apr 2020 14:03:00 +0200 Subject: [PATCH 0210/1454] Ensure brightness > 0 in ExtUI (#17611) --- .../lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 4e165aa448..325d0c07f2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -158,6 +158,8 @@ void InterfaceSettingsScreen::onIdle() { switch (cmd.track_tag(value)) { case 2: screen_data.InterfaceSettingsScreen.brightness = float(value) * 128 / 0xFFFF; + if (screen_data.InterfaceSettingsScreen.brightness > 1) + screen_data.InterfaceSettingsScreen.brightness = 1; CLCD::set_brightness(screen_data.InterfaceSettingsScreen.brightness); SaveSettingsDialogBox::settingsChanged(); break; From f779d1be3f53873e5b8b30d031b7c41100ca1068 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ond=C5=99ej=20Nov=C3=BD?= Date: Mon, 20 Apr 2020 14:05:58 +0200 Subject: [PATCH 0211/1454] HD44780 mapping for Czech accents (#17603) --- Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index a1258a3b10..45c4f94a43 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -678,6 +678,8 @@ static const hd44780_charmap_t g_hd44780_charmap_common[] PROGMEM = { {IV('ď'), 'd', 0}, // 010F {IV('đ'), 'd', 0}, // 0111 {IV('ę'), 'e', 0}, // 0119 + {IV('Ě'), 'E', 0}, // 011A + {IV('ě'), 'e', 0}, // 011B {IV('ğ'), 'g', 0}, // 011F {IV('İ'), 'I', 0}, // 0130 {IV('ı'), 'i', 0}, // 0131 @@ -688,6 +690,7 @@ static const hd44780_charmap_t g_hd44780_charmap_common[] PROGMEM = { {IV('ń'), 'n', 0}, // 0144 {IV('ň'), 'n', 0}, // 0148 + {IV('Ř'), 'R', 0}, // 0158 {IV('ř'), 'r', 0}, // 0159 {IV('Ś'), 'S', 0}, // 015A {IV('ś'), 's', 0}, // 015B From b55dd2cb82cbee78325f6a2e42458a2d48c06114 Mon Sep 17 00:00:00 2001 From: Thomas Hollstegge Date: Mon, 20 Apr 2020 14:07:23 +0200 Subject: [PATCH 0212/1454] Fix low contrast on Minipanel display (#17601) --- Marlin/src/inc/Conditionals_post.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 48490b75a5..ac4de5df10 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -289,8 +289,10 @@ #elif ENABLED(ULTI_CONTROLLER) #define _LCD_CONTRAST_INIT 127 #define _LCD_CONTRAST_MAX 254 -#elif EITHER(MAKRPANEL, MINIPANEL) +#elif ENABLED(MAKRPANEL) #define _LCD_CONTRAST_INIT 17 +#elif ENABLED(MINIPANEL) + #define _LCD_CONTRAST_INIT 150 #endif #ifdef _LCD_CONTRAST_INIT From 9338fb87e993757c7f403e97e9d607454a646171 Mon Sep 17 00:00:00 2001 From: "Zs.Antal" <45710979+AntoszHUN@users.noreply.github.com> Date: Mon, 20 Apr 2020 14:13:04 +0200 Subject: [PATCH 0213/1454] Update Hungarian language (#17593) --- Marlin/src/lcd/language/language_hu.h | 29 ++++++++++++++++----------- 1 file changed, 17 insertions(+), 12 deletions(-) diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index f282704abd..08cbd7ddcc 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -22,18 +22,22 @@ #pragma once /** - * Hungarian + * Magyar + * + * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html + * Marlin 2.0.x bugfix Magyar fordítása. A fordítást folyamatosan javítom és frissítem. + * A Magyar fordítást készítette: AntoszHUN + * * - * LCD Menu Messages - * See also http://marlinfw.org/docs/development/lcd_language.html * */ namespace Language_hu { - using namespace Language_en; // Inherit undefined strings from English + using namespace Language_en; // A fordítás az örökölt Amerikai Angol (English) karakterláncokat használja. +namespace Language_hu { constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Magyar") + PROGMEM Language_Str LANGUAGE = _UxGT("Magyar"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Kész."); PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); @@ -48,6 +52,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. Végállás"); PROGMEM Language_Str MSG_MAIN = _UxGT(""); @@ -469,7 +474,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Munkalámpa"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Fényerösség"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás Számláló"); @@ -505,13 +510,13 @@ namespace Language_hu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Fúvóka: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Túlfutás Szenzor"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás Táv. mm"); - PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Tájolási hiba"); + PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Tájolási hiba"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Szondázás hiba"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Túl hideg"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SZÁLVÁLASZTÁS"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("MMU Szoftver Feltöltése!"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU Szoftver Feltöltése!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Figyelmeztetés."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Nyomtatás Folytatása"); PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Folytatás..."); @@ -556,12 +561,12 @@ namespace Language_hu { PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); // - // Filamentváltó képernyők legfeljebb 3 sort jeleníthetnek meg egy 4 soros kijelzőn - // ...vagy legfeljebb 2 sor egy 3 soros kijelzőn + // Filament Change screens show up to 3 lines on a 4-line display + // ...or up to 2 lines on a 3-line display // #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nyomj gombot", "nyomtatás folytatáshoz")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkolás...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Várj míg", "szál csere", "indítás")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Szál behelyezés", "majd nyomj gombot", "a folytatáshoz")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nyomj gombot", "a fúvóka fűtéséhez")); @@ -573,7 +578,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd foltyat...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Parkolás...")); + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Kérlek Várj...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Behelyez majd katt")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Katt a fűtéshez")); From 90a432279bd53726e0e31ade3c88051c0eb938e0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Roman=20Morav=C4=8D=C3=ADk?= Date: Mon, 20 Apr 2020 14:13:33 +0200 Subject: [PATCH 0214/1454] Update Slovak language (#17588) --- Marlin/src/lcd/language/language_sk.h | 19 ++++++++++++++++++- 1 file changed, 18 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 53602af7c5..78c533d357 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -52,6 +52,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán."); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Chyba spúšťania USB"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Preteč. podprogramu"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znakov PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); PROGMEM Language_Str MSG_MAIN = _UxGT("Hlavná ponuka"); @@ -90,6 +91,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Zahriať ") PREHEAT_2_LABEL _UxGT(" nast."); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Vlastná teplota"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Schladiť"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Nastavenie lasera"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Vypnúť laser"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Zapnúť laser"); @@ -240,6 +242,8 @@ namespace Language_sk { PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Tryska ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Tryska zaparkovná"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); PROGMEM Language_Str MSG_BED = _UxGT("Podložka"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Komora"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Rýchlosť vent."); @@ -247,6 +251,11 @@ namespace Language_sk { PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Rýchlosť ex. vent."); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Rýchlosť ex. vent. ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Vent. riad. jedn."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Voľno. rýchl."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto-režím"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív. rýchl."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Doba nečinnosti"); PROGMEM Language_Str MSG_FLOW = _UxGT("Prietok"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Prietok ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Ovládanie"); @@ -307,6 +316,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Chyba: EEPROM CRC"); PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Chyba: EEPROM Index"); PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Chyba: Verzia EEPROM"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Nastav. uložené"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aktualizovať z SD"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reštart. tlačiar."); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Obnoviť"); @@ -323,6 +333,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Hotovo"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Naspäť"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Pokračovať"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Pozastavujem..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pozastaviť tlač"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Obnoviť tlač"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Zastaviť tlač"); @@ -337,6 +348,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Tlač pozastavená"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Tlačím..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Tlač zrušená"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Tlač dokončená"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Žiadny pohyb."); PROGMEM Language_Str MSG_KILLED = _UxGT("PRERUŠENÉ. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("ZASTAVENÉ. "); @@ -355,7 +367,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Zdvihnúť Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Primárna rýchl."); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Rýchl. retrakcie"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Vymeniť filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Vymeniť filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Zaviesť filament"); @@ -582,4 +593,10 @@ namespace Language_sk { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekcia"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Vyhladzovanie"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Vyrovnať os X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto-kalibrovať"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Vypršal čas ohrevu"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Zohriať"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Zohrievanie..."); } From cba58b1027b8192d71cc0505a8667d0b1b303218 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 20 Apr 2020 05:16:38 -0700 Subject: [PATCH 0215/1454] Fix "possible buffer overrun" warning (#17513) --- Marlin/src/lcd/menu/menu_ubl.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 4d7edbdfd1..a4db6da377 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -188,8 +188,8 @@ void _lcd_ubl_edit_mesh() { */ void _lcd_ubl_validate_custom_mesh() { char ubl_lcd_gcode[24]; - const int temp = TERN(HAS_HEATED_BED, custom_bed_temp, 0); - sprintf_P(ubl_lcd_gcode, PSTR("G28\nG26 C B%i H%i P"), temp, custom_hotend_temp); + const int16_t temp = TERN(HAS_HEATED_BED, custom_bed_temp, 0); + sprintf_P(ubl_lcd_gcode, PSTR("G28\nG26 C B%" PRIi16 " H%" PRIi16 " P"), temp, custom_hotend_temp); queue.inject(ubl_lcd_gcode); } From ccfd5c1010270493f0c7ddc7a5ab62dc5e09def3 Mon Sep 17 00:00:00 2001 From: Fabio Santos Date: Mon, 20 Apr 2020 06:08:00 -0700 Subject: [PATCH 0216/1454] Trinamic steppers Homing Phase (#17299) --- Marlin/Configuration_adv.h | 18 +++++-- Marlin/src/feature/tmc_util.h | 6 ++- Marlin/src/module/motion.cpp | 88 +++++++++++++++++++++++++++++++++-- 3 files changed, 104 insertions(+), 8 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 05c629d853..510a8536ac 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2272,9 +2272,9 @@ #define CHOPPER_TIMING CHOPPER_DEFAULT_12V /** - * Monitor Trinamic drivers for error conditions, - * like overtemperature and short to ground. - * In the case of overtemperature Marlin can decrease the driver current until error condition clears. + * Monitor Trinamic drivers + * for error conditions like overtemperature and short to ground. + * To manage over-temp Marlin can decrease the driver current until the error condition clears. * Other detected conditions can be used to stop the current print. * Relevant g-codes: * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. @@ -2351,6 +2351,18 @@ //#define IMPROVE_HOMING_RELIABILITY #endif + /** + * TMC Homing stepper phase. + * + * Improve homing repeatability by homing to stepper coil's nearest absolute + * phase position. Trinamic drivers use a stepper phase table with 1024 values + * spanning 4 full steps with 256 positions each (ergo, 1024 positions). + * Full step positions (128, 384, 640, 896) have the highest holding torque. + * + * Values from 0..1023, -1 to disable homing phase for that axis. + */ + //#define TMC_HOME_PHASE { 896, 896, 896 } + /** * Beta feature! * Create a 50/50 square wave step pulse optimal for stepper drivers. diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index ccae8b660c..6838aa433c 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -105,7 +105,8 @@ class TMCMarlin : public TMC, public TMCStorage { this->val_mA = mA; TMC::rms_current(mA, mult); } - + inline uint16_t get_microstep_counter() { return TMC::MSCNT(); } + #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return this->en_pwm_mode(); } @@ -170,6 +171,7 @@ class TMCMarlin : public TMC220 this->val_mA = mA; TMC2208Stepper::rms_current(mA, mult); } + inline uint16_t get_microstep_counter() { return TMC2208Stepper::MSCNT(); } #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } @@ -216,6 +218,7 @@ class TMCMarlin : public TMC220 this->val_mA = mA; TMC2209Stepper::rms_current(mA, mult); } + inline uint16_t get_microstep_counter() { return TMC2209Stepper::MSCNT(); } #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } @@ -273,6 +276,7 @@ class TMCMarlin : public TMC266 this->val_mA = mA; TMC2660Stepper::rms_current(mA); } + inline uint16_t get_microstep_counter() { return TMC2660Stepper::mstep(); } #if USE_SENSORLESS inline int16_t homing_threshold() { return TMC2660Stepper::sgt(); } diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 3c89b933d8..c2301aa343 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1483,6 +1483,80 @@ void set_axis_not_trusted(const AxisEnum axis) { #endif } +/** + * Move the axis back to its home_phase if set and driver is capable (TMC) + * + * Improves homing repeatability by homing to stepper coil's nearest absolute + * phase position. Trinamic drivers use a stepper phase table with 1024 values + * spanning 4 full steps with 256 positions each (ergo, 1024 positions). + */ +void backout_to_tmc_homing_phase(const AxisEnum axis) { + #ifdef TMC_HOME_PHASE + const abc_long_t home_phase = TMC_HOME_PHASE; + + // check if home phase is disabled for this axis. + if (home_phase[axis] < 0) return; + + int16_t axisMicrostepSize; + int16_t phaseCurrent; + bool invertDir; + + switch (axis) { + #ifdef X_MICROSTEPS + case X_AXIS: + axisMicrostepSize = 256 / (X_MICROSTEPS); + phaseCurrent = stepperX.get_microstep_counter(); + invertDir = INVERT_X_DIR; + break; + #endif + #ifdef Y_MICROSTEPS + case Y_AXIS: + axisMicrostepSize = 256 / (Y_MICROSTEPS); + phaseCurrent = stepperY.get_microstep_counter(); + invertDir = INVERT_Y_DIR; + break; + #endif + #ifdef Z_MICROSTEPS + case Z_AXIS: + axisMicrostepSize = 256 / (Z_MICROSTEPS); + phaseCurrent = stepperZ.get_microstep_counter(); + invertDir = INVERT_Z_DIR; + break; + #endif + default: return; + } + + // Depending on invert dir measure the distance to nearest home phase. + int16_t phaseDelta = (invertDir ? -1 : 1) * (home_phase[axis] - phaseCurrent); + + // Check if home distance within endstop assumed repeatability noise of .05mm and warn. + if (ABS(phaseDelta) * planner.steps_to_mm[axis] / axisMicrostepSize < 0.05f) + DEBUG_ECHOLNPAIR("Selected home phase ", home_phase[axis], + " too close to endstop trigger phase ", phaseCurrent, + ". Pick a different phase for ", axis_codes[axis]); + + // Skip to next if target position is behind current. So it only moves away from endstop. + if (phaseDelta < 0) phaseDelta += 1024; + + // Get the integer µsteps to target. Unreachable phase? Consistently stop at the µstep before / after based on invertDir. + const float mmDelta = -(int16_t(phaseDelta / axisMicrostepSize) * planner.steps_to_mm[axis] * (Z_HOME_DIR)); + + // optional debug messages. + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOLNPAIR( + "Endstop ", axis_codes[axis], " hit at Phase:", phaseCurrent, + " Delta:", phaseDelta, " Distance:", mmDelta + ); + } + + if (mmDelta != 0) { + // retrace by the amount computed in mmDelta. + do_homing_move(axis, mmDelta, get_homing_bump_feedrate(axis)); + } + #endif +} + + /** * Home an individual "raw axis" to its endstop. * This applies to XYZ on Cartesian and Core robots, and @@ -1742,6 +1816,9 @@ void homeaxis(const AxisEnum axis) { } #endif + // move back to homing phase if configured and capable + backout_to_tmc_homing_phase(axis); + #if IS_SCARA set_axis_is_at_home(axis); @@ -1753,10 +1830,13 @@ void homeaxis(const AxisEnum axis) { // so here it re-homes each tower in turn. // Delta homing treats the axes as normal linear axes. - // retrace by the amount specified in delta_endstop_adj + additional dist in order to have minimum steps - if (delta_endstop_adj[axis] * Z_HOME_DIR <= 0) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("delta_endstop_adj:"); - do_homing_move(axis, delta_endstop_adj[axis] - (MIN_STEPS_PER_SEGMENT + 1) * planner.steps_to_mm[axis] * Z_HOME_DIR); + const float adjDistance = delta_endstop_adj[axis], + minDistance = (MIN_STEPS_PER_SEGMENT) * planner.steps_to_mm[axis]; + + // Retrace by the amount specified in delta_endstop_adj if more than min steps. + if (adjDistance * (Z_HOME_DIR) < 0 && ABS(adjDistance) > minDistance) { // away from endstop, more than min distance + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("adjDistance:", adjDistance); + do_homing_move(axis, adjDistance, get_homing_bump_feedrate(axis)); } #else // CARTESIAN / CORE From 875cd4e081ef6885aa2593d125b2db5ff393a391 Mon Sep 17 00:00:00 2001 From: Mathias Rasmussen Date: Mon, 20 Apr 2020 16:17:55 +0200 Subject: [PATCH 0217/1454] Remove 'Media Released' message (#17272) Co-authored-by: Scott Lahteine --- Marlin/src/lcd/language/language_cz.h | 1 - Marlin/src/lcd/language/language_de.h | 1 - Marlin/src/lcd/language/language_en.h | 1 - Marlin/src/lcd/language/language_es.h | 1 - Marlin/src/lcd/language/language_fr.h | 1 - Marlin/src/lcd/language/language_gl.h | 1 - Marlin/src/lcd/language/language_hu.h | 1 - Marlin/src/lcd/language/language_it.h | 1 - Marlin/src/lcd/language/language_jp_kana.h | 1 - Marlin/src/lcd/language/language_pl.h | 1 - Marlin/src/lcd/language/language_ru.h | 1 - Marlin/src/lcd/language/language_sk.h | 1 - Marlin/src/lcd/language/language_tr.h | 1 - Marlin/src/lcd/language/language_vi.h | 1 - Marlin/src/lcd/language/language_zh_TW.h | 1 - Marlin/src/lcd/menu/menu_main.cpp | 2 -- 16 files changed, 17 deletions(-) diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 7fffc21806..c8f0e6b13b 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -49,7 +49,6 @@ namespace Language_cz { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Rušení..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Médium vloženo"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Médium vyjmuto"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Médium uvolněno"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Čekání na médium"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Chyba čtení média"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB odstraněno"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index f4fe9d1cff..9f874e979d 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -43,7 +43,6 @@ namespace Language_de { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Abbruch..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Medium erkannt"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Medium entfernt"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Medium freigegeben"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Warten auf Medium"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index fad678eada..a3e25d9145 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -47,7 +47,6 @@ namespace Language_en { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Aborting..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media Inserted"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media Removed"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Media Released"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Waiting for media"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Media read error"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index dd06ac5dcc..015663e885 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -43,7 +43,6 @@ namespace Language_es { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD/USB insertado"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD/USB retirado"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD/USB lanzado"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Esperando al SD/USB"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/USB"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 816113a208..2fca6adbb4 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -44,7 +44,6 @@ namespace Language_fr { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Annulation..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Média inséré"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Média retiré"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Média libéré"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Attente média"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Err lecture média"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB débranché"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 1fb430bfb6..fa9f371971 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -45,7 +45,6 @@ namespace Language_gl { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD/USB lanzado"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/USB"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 08cbd7ddcc..e07dd4c64e 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -47,7 +47,6 @@ namespace Language_hu { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Megszakítás..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tároló Behelyezve"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tároló Eltávolítva"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Tároló Leválasztva"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 0aed8a6cfa..d17c100490 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -45,7 +45,6 @@ namespace Language_it { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Annullando..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media inserito"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media rimosso"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Media rilasciato"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Aspettando media"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo media"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 62b7daf705..f6d4ede51f 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -46,7 +46,6 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("メディアガソウニュウサレマシタ"); // "Card inserted" PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("メディアガアリマセン"); // "Card removed" PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("メディアノトリダシ"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("メディアガアリマセン"); // "Card removed" PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("エンドストップ"); // "Endstops" // Max length 8 characters PROGMEM Language_Str MSG_MAIN = _UxGT("メイン"); // "Main" PROGMEM Language_Str MSG_AUTOSTART = _UxGT("ジドウカイシ"); // "Autostart" diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index d263726e13..0cb4f25499 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -44,7 +44,6 @@ namespace Language_pl { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Przerywanie..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Karta zwolniona"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 69d9d61207..b559acad46 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -40,7 +40,6 @@ namespace Language_ru { PROGMEM Language_Str MSG_BACK = _UxGT("Назад"); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Карта вставлена"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Карта извлечена"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD карта не активна"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Эндстопы"); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр. эндстопы"); PROGMEM Language_Str MSG_MAIN = _UxGT("Меню"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 78c533d357..bb68ec1c38 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -47,7 +47,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Ruším..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta vložená"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta vybraná"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Karta odpojená"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Čakám na kartu"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán."); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index e1d3bd898c..a33b0d315d 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -49,7 +49,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Durduruluyor..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD K. Yerleştirildi."); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD Kart Çıkarıldı."); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD Kart Serbest"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("SD Kart Bekleniyor"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Kart Okuma Hatası"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB Çıkarıldı"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 71c8eebdd8..781a1242b8 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -39,7 +39,6 @@ namespace Language_vi { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Đang hủy bỏ..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Phương tiện được cắm vào"); // Media inserted PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Phương tiện được rút ra"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Phương tiện đã phát hành"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Chờ đợi phương tiện"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Lỗi đọc phương tiện"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB được rút ra"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 274d692776..6bb7d759f6 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -42,7 +42,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("正在中止..."); //"Aborting..." PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("記憶卡已插入"); //"Card inserted" PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("記憶卡被拔出"); //"Card removed" - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("記憶卡被釋放"); //"Media Released" PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("等待記憶卡"); //"Waiting for media" PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("記憶卡讀取錯誤"); //"Media read error" PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB裝置已移除"); //"USB device removed" diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index d98670922c..b21cb7e556 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -135,7 +135,6 @@ void menu_main() { ACTION_ITEM(MSG_NO_MEDIA, nullptr); #else GCODES_ITEM(MSG_ATTACH_MEDIA, M21_STR); - ACTION_ITEM(MSG_MEDIA_RELEASED, nullptr); #endif } @@ -229,7 +228,6 @@ void menu_main() { ACTION_ITEM(MSG_NO_MEDIA, nullptr); #else GCODES_ITEM(MSG_ATTACH_MEDIA, M21_STR); - ACTION_ITEM(MSG_MEDIA_RELEASED, nullptr); #endif } From 000ec9fc139413c7702e8e295a29a21f6a6226e8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 20 Apr 2020 09:43:15 -0500 Subject: [PATCH 0218/1454] Ensure language.h include order See #17604 --- Marlin/Configuration_adv.h | 4 ++-- Marlin/src/core/language.h | 8 +++----- Marlin/src/core/serial.cpp | 2 +- Marlin/src/feature/pause.cpp | 1 - Marlin/src/gcode/feature/pause/G60.cpp | 1 - Marlin/src/gcode/feature/pause/G61.cpp | 1 - Marlin/src/lcd/lcdprint.cpp | 2 +- Marlin/src/module/configuration_store.cpp | 1 - Marlin/src/module/planner.cpp | 1 - Marlin/src/module/planner_bezier.cpp | 1 - Marlin/src/module/stepper.cpp | 1 - Marlin/src/module/temperature.cpp | 1 - Marlin/src/sd/cardreader.cpp | 1 - 13 files changed, 7 insertions(+), 18 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 510a8536ac..63c41ebd0e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -936,7 +936,7 @@ // Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS. // These correspond to the physical drivers, so be mindful if the order is changed. - #define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO + #define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO //#define DIGIPOT_USE_RAW_VALUES // Use DIGIPOT_MOTOR_CURRENT raw wiper values (instead of A4988 motor currents) @@ -2358,7 +2358,7 @@ * phase position. Trinamic drivers use a stepper phase table with 1024 values * spanning 4 full steps with 256 positions each (ergo, 1024 positions). * Full step positions (128, 384, 640, 896) have the highest holding torque. - * + * * Values from 0..1023, -1 to disable homing phase for that axis. */ //#define TMC_HOME_PHASE { 896, 896, 896 } diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index e662fffd37..40a0d7b8cb 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -81,11 +81,9 @@ #ifdef CUSTOM_MACHINE_NAME #undef MACHINE_NAME #define MACHINE_NAME CUSTOM_MACHINE_NAME -#else - #ifdef DEFAULT_MACHINE_NAME - #undef MACHINE_NAME - #define MACHINE_NAME DEFAULT_MACHINE_NAME - #endif +#elif defined(DEFAULT_MACHINE_NAME) + #undef MACHINE_NAME + #define MACHINE_NAME DEFAULT_MACHINE_NAME #endif #ifndef MACHINE_UUID diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 304aa09a8a..bf0df9b3b7 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -21,7 +21,7 @@ */ #include "serial.h" -#include "language.h" +#include "../inc/MarlinConfig.h" uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 657f427656..3b4ac9c27a 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -53,7 +53,6 @@ #include "../lcd/extui/ui_api.h" #endif -#include "../core/language.h" #include "../lcd/ultralcd.h" #if HAS_BUZZER diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 45a8734ca3..73bd0c2489 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -24,7 +24,6 @@ #if SAVED_POSITIONS -#include "../../../core/language.h" #include "../../gcode.h" #include "../../../module/motion.h" diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index 60e6bcf040..a0526d4c5d 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -24,7 +24,6 @@ #if SAVED_POSITIONS -#include "../../../core/language.h" #include "../../../module/planner.h" #include "../../gcode.h" #include "../../../module/motion.h" diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index b19ab38edb..012c328a00 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -28,8 +28,8 @@ #if HAS_SPI_LCD +#include "../inc/MarlinConfig.h" #include "lcdprint.h" -#include "../core/language.h" /** * lcd_put_u8str_ind_P diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index cdc4432a53..d201a45e6d 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -51,7 +51,6 @@ #include "stepper.h" #include "temperature.h" #include "../lcd/ultralcd.h" -#include "../core/language.h" #include "../libs/vector_3.h" // for matrix_3x3 #include "../gcode/gcode.h" #include "../MarlinCore.h" diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index b7e2681141..5cd83fd8d8 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -67,7 +67,6 @@ #include "motion.h" #include "temperature.h" #include "../lcd/ultralcd.h" -#include "../core/language.h" #include "../gcode/parser.h" #include "../MarlinCore.h" diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index 7ea3956436..1377abc034 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -36,7 +36,6 @@ #include "temperature.h" #include "../MarlinCore.h" -#include "../core/language.h" #include "../gcode/queue.h" // See the meaning in the documentation of cubic_b_spline(). diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index f77a596b08..94da5f0076 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -97,7 +97,6 @@ Stepper stepper; // Singleton #include "temperature.h" #include "../lcd/ultralcd.h" -#include "../core/language.h" #include "../gcode/queue.h" #include "../sd/cardreader.h" #include "../MarlinCore.h" diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 0ca7535ec7..c72eb6f371 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -30,7 +30,6 @@ #include "../MarlinCore.h" #include "../lcd/ultralcd.h" #include "planner.h" -#include "../core/language.h" #include "../HAL/shared/Delay.h" #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 1c8c581b3c..389ef110b3 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -30,7 +30,6 @@ #include "../lcd/ultralcd.h" #include "../module/planner.h" // for synchronize #include "../module/printcounter.h" -#include "../core/language.h" #include "../gcode/queue.h" #include "../module/configuration_store.h" From abd42e5dea4670fd3f4c9177caabb31f391edbeb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ond=C5=99ej=20Nov=C3=BD?= Date: Mon, 20 Apr 2020 18:32:21 +0200 Subject: [PATCH 0219/1454] Fix M125 unretract length (#17623) --- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 79ed6e785a..4039e8c53d 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -94,7 +94,7 @@ void GcodeSuite::M125() { #endif if (!sd_printing || show_lcd) { wait_for_confirmation(false, 0); - resume_print(0, 0, PAUSE_PARK_RETRACT_LENGTH, 0); + resume_print(0, 0, -retract, 0); } } } From eb91dbce421fd766d82a80b41e5498cc7618c5d7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 21 Apr 2020 00:03:16 +0000 Subject: [PATCH 0220/1454] [cron] Bump distribution date (2020-04-21) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2c3f6e4eb7..de23a23bcc 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-20" + #define STRING_DISTRIBUTION_DATE "2020-04-21" #endif /** From a5b2e3e63c1b20dfd3657ee58819deb36454488b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Apr 2020 12:49:22 -0500 Subject: [PATCH 0221/1454] Fix Mixer::reset_vtools bug Fixes #17635 --- Marlin/src/feature/mixing.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index fe0f19d13e..5ef0e918f7 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -98,7 +98,7 @@ void Mixer::normalize(const uint8_t tool_index) { void Mixer::reset_vtools() { // Virtual Tools 0, 1, 2, 3 = Filament 1, 2, 3, 4, etc. // Every virtual tool gets a pure filament - LOOP_L_N(t, MIXING_VIRTUAL_TOOLS && t < MIXING_STEPPERS) + LOOP_L_N(t, _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS)) MIXER_STEPPER_LOOP(i) color[t][i] = (t == i) ? COLOR_A_MASK : 0; From 2ae00db43e8cc987c3e29cacd3368e791516e910 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Apr 2020 15:27:36 -0500 Subject: [PATCH 0222/1454] Move G26 heading up --- Marlin/src/gcode/bedlevel/G26.cpp | 97 ++++++++++++++----------------- 1 file changed, 45 insertions(+), 52 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 28fdf581ff..0867e1e010 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -20,54 +20,6 @@ * */ -/** - * Marlin Firmware -- G26 - Mesh Validation Tool - */ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(G26_MESH_VALIDATION) - -#define G26_OK false -#define G26_ERR true - -#include "../../gcode/gcode.h" -#include "../../feature/bedlevel/bedlevel.h" - -#include "../../MarlinCore.h" -#include "../../module/planner.h" -#include "../../module/stepper.h" -#include "../../module/motion.h" -#include "../../module/tool_change.h" -#include "../../module/temperature.h" -#include "../../lcd/ultralcd.h" - -#define EXTRUSION_MULTIPLIER 1.0 -#define PRIME_LENGTH 10.0 -#define OOZE_AMOUNT 0.3 - -#define INTERSECTION_CIRCLE_RADIUS 5 -#define CROSSHAIRS_SIZE 3 - -#ifndef G26_RETRACT_MULTIPLIER - #define G26_RETRACT_MULTIPLIER 1.0 // x 1mm -#endif - -#ifndef G26_XY_FEEDRATE - #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE() / 3.0) -#endif - -#if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS - #error "CROSSHAIRS_SIZE must be less than INTERSECTION_CIRCLE_RADIUS." -#endif - -#define G26_OK false -#define G26_ERR true - -#if ENABLED(ARC_SUPPORT) - void plan_arc(const xyze_pos_t &cart, const ab_float_t &offset, const uint8_t clockwise); -#endif - /** * G26 Mesh Validation Tool * @@ -141,13 +93,54 @@ * Y # Y Coord. Specify the starting location of the drawing activity. */ -// External references +#include "../../inc/MarlinConfig.h" -// Private functions +#if ENABLED(G26_MESH_VALIDATION) + +#define G26_OK false +#define G26_ERR true + +#include "../../gcode/gcode.h" +#include "../../feature/bedlevel/bedlevel.h" + +#include "../../MarlinCore.h" +#include "../../module/planner.h" +#include "../../module/stepper.h" +#include "../../module/motion.h" +#include "../../module/tool_change.h" +#include "../../module/temperature.h" +#include "../../lcd/ultralcd.h" + +#define EXTRUSION_MULTIPLIER 1.0 +#define PRIME_LENGTH 10.0 +#define OOZE_AMOUNT 0.3 + +#define INTERSECTION_CIRCLE_RADIUS 5 +#define CROSSHAIRS_SIZE 3 + +#ifndef G26_RETRACT_MULTIPLIER + #define G26_RETRACT_MULTIPLIER 1.0 // x 1mm +#endif + +#ifndef G26_XY_FEEDRATE + #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE() / 3.0) +#endif + +#if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS + #error "CROSSHAIRS_SIZE must be less than INTERSECTION_CIRCLE_RADIUS." +#endif + +#define G26_OK false +#define G26_ERR true + +#if ENABLED(ARC_SUPPORT) + void plan_arc(const xyze_pos_t &cart, const ab_float_t &offset, const uint8_t clockwise); +#endif + +constexpr float g26_e_axis_feedrate = 0.025; static MeshFlags circle_flags, horizontal_mesh_line_flags, vertical_mesh_line_flags; -float g26_e_axis_feedrate = 0.025, - random_deviation = 0.0; +float random_deviation = 0.0; static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched // retracts/recovers won't result in a bad state. From d96c769fd6c8dcbe33b376ecbce19bd8c3c163cc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Apr 2020 01:11:56 -0500 Subject: [PATCH 0223/1454] Move Power Loss Recovery check --- Marlin/src/MarlinCore.cpp | 4 ---- Marlin/src/feature/powerloss.cpp | 4 ++-- Marlin/src/sd/cardreader.cpp | 9 +++++++-- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 1b78d45a01..8539114488 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1161,10 +1161,6 @@ void setup() { SETUP_RUN(est_init()); #endif - #if ENABLED(POWER_LOSS_RECOVERY) - SETUP_RUN(recovery.check()); - #endif - #if ENABLED(USE_WATCHDOG) SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 77d0047a5c..397b88d362 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -100,10 +100,10 @@ void PrintJobRecovery::changed() { * If a saved state exists send 'M1000 S' to initiate job recovery. */ void PrintJobRecovery::check() { - if (!card.isMounted()) card.mount(); + //if (!card.isMounted()) card.mount(); if (card.isMounted()) { load(); - if (!valid()) return purge(); + if (!valid()) return cancel(); queue.inject_P(PSTR("M1000 S")); } } diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 389ef110b3..25a0bd479e 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -408,8 +408,13 @@ void CardReader::manage_media() { ui.media_changed(old_stat, stat); // Update the UI - if (stat && old_stat == 2) // First mount? - beginautostart(); // Look for autostart files soon + if (stat && old_stat == 2) { // First mount? + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.check(); + #else + beginautostart(); // Look for autostart files soon + #endif + } } } From 5de87361e90a1f20b19e9c04e92c2207579135cc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 14 Apr 2020 17:33:34 -0500 Subject: [PATCH 0224/1454] Call first_load from manage_media --- Marlin/src/sd/cardreader.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 25a0bd479e..f28c7ea5f0 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -368,9 +368,6 @@ void CardReader::mount() { else { flag.mounted = true; SERIAL_ECHO_MSG(STR_SD_CARD_OK); - #if ENABLED(SDCARD_EEPROM_EMULATION) - settings.first_load(); - #endif } cdroot(); @@ -408,12 +405,17 @@ void CardReader::manage_media() { ui.media_changed(old_stat, stat); // Update the UI - if (stat && old_stat == 2) { // First mount? - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.check(); - #else - beginautostart(); // Look for autostart files soon + if (stat) { + #if ENABLED(SDCARD_EEPROM_EMULATION) + settings.first_load(); #endif + if (old_stat == 2) { // First mount? + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.check(); + #else + beginautostart(); // Look for autostart files soon + #endif + } } } } From c3946dd0174b63136f9c8437ca159a17ddc68512 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Apr 2020 18:37:04 -0500 Subject: [PATCH 0225/1454] Add a warning on LA + S-Curve --- Marlin/Configuration_adv.h | 1 + Marlin/src/inc/SanityCheck.h | 3 +++ 2 files changed, 4 insertions(+) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 63c41ebd0e..e73964e245 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1542,6 +1542,7 @@ //#define EXTRA_LIN_ADVANCE_K // Enable for second linear advance constants #define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed //#define LA_DEBUG // If enabled, this will generate debug information output over USB. + //#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration #endif // @section leveling diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index b30097705f..1b51154acf 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -964,6 +964,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS WITHIN(LIN_ADVANCE_K, 0, 10), "LIN_ADVANCE_K must be a value from 0 to 10 (Changed in LIN_ADVANCE v1.5, Marlin 1.1.9)." ); + #if ENABLED(S_CURVE_ACCELERATION) && DISABLED(EXPERIMENTAL_SCURVE) + #error "LIN_ADVANCE and S_CURVE_ACCELERATION may not play well together! Enable EXPERIMENTAL_SCURVE to continue." + #endif #endif /** From d34c22ac22dc20503f619449fe55161e82651ad3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Apr 2020 17:22:43 -0500 Subject: [PATCH 0226/1454] Skip redundant file/dir tests --- Marlin/src/sd/cardreader.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index f28c7ea5f0..6f2557cda8 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -154,12 +154,13 @@ char *createFilename(char * const buffer, const dir_t &p) { // Return 'true' if the item is a folder or G-code file // bool CardReader::is_dir_or_gcode(const dir_t &p) { - uint8_t pn0 = p.name[0]; + //uint8_t pn0 = p.name[0]; - if ( pn0 == DIR_NAME_FREE || pn0 == DIR_NAME_DELETED // Clear or Deleted entry - || pn0 == '.' || longFilename[0] == '.' // Hidden file - || !DIR_IS_FILE_OR_SUBDIR(&p) // Not a File or Directory - || (p.attributes & DIR_ATT_HIDDEN) // Hidden by attribute + if ( (p.attributes & DIR_ATT_HIDDEN) // Hidden by attribute + // When readDir() > 0 these must be false: + //|| pn0 == DIR_NAME_FREE || pn0 == DIR_NAME_DELETED // Clear or Deleted entry + //|| pn0 == '.' || longFilename[0] == '.' // Hidden file + //|| !DIR_IS_FILE_OR_SUBDIR(&p) // Not a File or Directory ) return false; flag.filenameIsDir = DIR_IS_SUBDIR(&p); // We know it's a File or Folder From 1563d128d8a856d081f96d27ff2cbd5d43bfa733 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 22 Apr 2020 00:03:05 +0000 Subject: [PATCH 0227/1454] [cron] Bump distribution date (2020-04-22) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index de23a23bcc..02682d0b86 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-21" + #define STRING_DISTRIBUTION_DATE "2020-04-22" #endif /** From d666ef00e03f5d7c219e9c6ff5a56461bbf194d3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Apr 2020 18:51:28 -0500 Subject: [PATCH 0228/1454] Prevent 'I2C_EEPROM' on LPC176x --- Marlin/src/HAL/LPC1768/eeprom_api.h | 26 ------------------- Marlin/src/HAL/LPC1768/eeprom_flash.cpp | 2 +- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 2 +- .../src/HAL/LPC1768/inc/Conditionals_post.h | 4 ++- 4 files changed, 5 insertions(+), 29 deletions(-) delete mode 100644 Marlin/src/HAL/LPC1768/eeprom_api.h diff --git a/Marlin/src/HAL/LPC1768/eeprom_api.h b/Marlin/src/HAL/LPC1768/eeprom_api.h deleted file mode 100644 index f874eac58a..0000000000 --- a/Marlin/src/HAL/LPC1768/eeprom_api.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include "../shared/eeprom_api.h" - -#define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp index 9225807480..ea4ef7c66c 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp @@ -40,7 +40,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) -#include "eeprom_api.h" +#include "../shared/eeprom_api.h" extern "C" { #include diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index 2ae5f25271..ce76a5a439 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -26,7 +26,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "eeprom_api.h" +#include "../shared/eeprom_api.h" #include #include diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index 490cfd50e8..25c3b79cd1 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -21,6 +21,8 @@ */ #pragma once -#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#undef I2C_EEPROM // Arduino framework provides code for I2C + +#if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION #endif From 0fec478562c4fb0959831aa169c24dec90e9e74e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Apr 2020 21:26:25 -0500 Subject: [PATCH 0229/1454] Wrangle HAL EEPROM types --- Marlin/src/HAL/ESP32/{eeprom_impl.cpp => eeprom.cpp} | 0 Marlin/src/HAL/LINUX/{eeprom_impl.cpp => eeprom.cpp} | 0 Marlin/src/HAL/SAMD51/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/STM32/{eeprom_impl.cpp => eeprom_wired.cpp} | 0 Marlin/src/HAL/STM32F1/{eeprom.cpp => eeprom_wired.cpp} | 0 Marlin/src/HAL/TEENSY31_32/{eeprom_impl.cpp => eeprom.cpp} | 4 ++-- Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h | 5 ++--- Marlin/src/HAL/TEENSY35_36/eeprom.cpp | 4 ++-- Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h | 4 ++++ Marlin/src/inc/Conditionals_post.h | 4 +++- 10 files changed, 14 insertions(+), 9 deletions(-) rename Marlin/src/HAL/ESP32/{eeprom_impl.cpp => eeprom.cpp} (100%) rename Marlin/src/HAL/LINUX/{eeprom_impl.cpp => eeprom.cpp} (100%) rename Marlin/src/HAL/STM32/{eeprom_impl.cpp => eeprom_wired.cpp} (100%) rename Marlin/src/HAL/STM32F1/{eeprom.cpp => eeprom_wired.cpp} (100%) rename Marlin/src/HAL/TEENSY31_32/{eeprom_impl.cpp => eeprom.cpp} (97%) diff --git a/Marlin/src/HAL/ESP32/eeprom_impl.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp similarity index 100% rename from Marlin/src/HAL/ESP32/eeprom_impl.cpp rename to Marlin/src/HAL/ESP32/eeprom.cpp diff --git a/Marlin/src/HAL/LINUX/eeprom_impl.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp similarity index 100% rename from Marlin/src/HAL/LINUX/eeprom_impl.cpp rename to Marlin/src/HAL/LINUX/eeprom.cpp diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index 490cfd50e8..24ff12cf19 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -21,6 +21,6 @@ */ #pragma once -#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/STM32/eeprom_impl.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp similarity index 100% rename from Marlin/src/HAL/STM32/eeprom_impl.cpp rename to Marlin/src/HAL/STM32/eeprom_wired.cpp diff --git a/Marlin/src/HAL/STM32F1/eeprom.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp similarity index 100% rename from Marlin/src/HAL/STM32F1/eeprom.cpp rename to Marlin/src/HAL/STM32F1/eeprom_wired.cpp diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp similarity index 97% rename from Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp rename to Marlin/src/HAL/TEENSY31_32/eeprom.cpp index 96499d4f19..a00c1062aa 100644 --- a/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp @@ -20,7 +20,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) +#if USE_WIRED_EEPROM #include "../shared/eeprom_api.h" @@ -58,5 +58,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -#endif // EEPROM_SETTINGS +#endif // USE_WIRED_EEPROM #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h index 11603c9ef4..fb93947fd2 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h @@ -21,7 +21,6 @@ */ #pragma once -// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) - #define SDCARD_EEPROM_EMULATION +#if USE_FALLBACK_EEPROM + #define USE_WIRED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index c66a45e2a5..0ee686de13 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -25,7 +25,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) +#if USE_WIRED_EEPROM #include "../shared/eeprom_api.h" #include @@ -66,5 +66,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return E2END + 1; } -#endif // EEPROM_SETTINGS +#endif // USE_WIRED_EEPROM #endif // __MK64FX512__ || __MK66FX1M0__ diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h index 0285c52ee3..fb93947fd2 100644 --- a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h +++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h @@ -20,3 +20,7 @@ * */ #pragma once + +#if USE_FALLBACK_EEPROM + #define USE_WIRED_EEPROM 1 +#endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ac4de5df10..e8279475c7 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -39,7 +39,9 @@ #if ENABLED(EEPROM_SETTINGS) // EEPROM type may be defined by compile flags, configs, HALs, or pins // Set additional flags to let HALs choose in their Conditionals_post.h - #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM) + #if ANY(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define USE_EMULATED_EEPROM 1 + #elif ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM) #define USE_WIRED_EEPROM 1 #else #define USE_FALLBACK_EEPROM 1 From 5a5be7e287183e633ee3235ee1bcd79a72a1a1f5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Apr 2020 21:29:52 -0500 Subject: [PATCH 0230/1454] Reorder setup, with serial early --- Marlin/src/HAL/STM32/HAL.cpp | 18 ++++---- Marlin/src/MarlinCore.cpp | 83 ++++++++++++++++-------------------- 2 files changed, 46 insertions(+), 55 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 77f8d27640..602c1b5022 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -76,16 +76,16 @@ void HAL_init() { #endif #if ENABLED(SRAM_EEPROM_EMULATION) - // Enable access to backup SRAM - __HAL_RCC_PWR_CLK_ENABLE(); - HAL_PWR_EnableBkUpAccess(); - __HAL_RCC_BKPSRAM_CLK_ENABLE(); + // Enable access to backup SRAM + __HAL_RCC_PWR_CLK_ENABLE(); + HAL_PWR_EnableBkUpAccess(); + __HAL_RCC_BKPSRAM_CLK_ENABLE(); - // Enable backup regulator - LL_PWR_EnableBkUpRegulator(); - // Wait until backup regulator is initialized - while (!LL_PWR_IsActiveFlag_BRR()); - #endif // EEPROM_EMULATED_SRAM + // Enable backup regulator + LL_PWR_EnableBkUpRegulator(); + // Wait until backup regulator is initialized + while (!LL_PWR_IsActiveFlag_BRR()); + #endif #if HAS_TMC_SW_SERIAL SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 8539114488..7aff3b5752 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -889,52 +889,15 @@ void setup() { #endif #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0) - HAL_init(); - - #if HAS_L64XX - L64xxManager.init(); // Set up SPI, init drivers - #endif - - #if ENABLED(SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) - OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode - #endif - - #if ENABLED(DISABLE_DEBUG) + #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) // Disable any hardware debug to free up pins for IO - #ifdef JTAGSWD_DISABLE + #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) JTAGSWD_DISABLE(); #elif defined(JTAG_DISABLE) JTAG_DISABLE(); #else - #error "DISABLE_DEBUG is not supported for the selected MCU/Board" + #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." #endif - #elif ENABLED(DISABLE_JTAG) - // Disable JTAG to free up pins for IO - #ifdef JTAG_DISABLE - JTAG_DISABLE(); - #else - #error "DISABLE_JTAG is not supported for the selected MCU/Board" - #endif - #endif - - #if HAS_FILAMENT_SENSOR - runout.setup(); - #endif - - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.setup(); - #endif - - setup_killpin(); - - #if HAS_TMC220x - tmc_serial_begin(); - #endif - - setup_powerhold(); - - #if HAS_STEPPER_RESET - disableStepperDrivers(); #endif #if NUM_SERIAL > 0 @@ -946,10 +909,38 @@ void setup() { serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #endif + SERIAL_ECHO_MSG("start"); #endif - SERIAL_ECHOLNPGM("start"); - SERIAL_ECHO_START(); + SETUP_RUN(HAL_init()); + + #if HAS_L64XX + SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers + #endif + + #if ENABLED(SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) + OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode + #endif + + #if HAS_FILAMENT_SENSOR + SETUP_RUN(runout.setup()); + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + SETUP_RUN(recovery.setup()); + #endif + + SETUP_RUN(setup_killpin()); + + #if HAS_TMC220x + SETUP_RUN(tmc_serial_begin()); + #endif + + SETUP_RUN(setup_powerhold()); + + #if HAS_STEPPER_RESET + SETUP_RUN(disableStepperDrivers()); + #endif #if HAS_TMC_SPI #if DISABLED(TMC_USE_SW_SPI) @@ -966,7 +957,7 @@ void setup() { SETUP_RUN(esp_wifi_init()); // Check startup - does nothing if bootloader sets MCUSR to 0 - byte mcu = HAL_get_reset_source(); + const byte mcu = HAL_get_reset_source(); if (mcu & 1) SERIAL_ECHOLNPGM(STR_POWERUP); if (mcu & 2) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & 4) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); @@ -991,9 +982,6 @@ void setup() { SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); - // UI must be initialized before EEPROM - // (because EEPROM code calls the UI). - // Set up LEDs early #if HAS_COLOR_LEDS SETUP_RUN(leds.setup()); @@ -1003,6 +991,9 @@ void setup() { SETUP_RUN(controllerFan.setup()); #endif + // UI must be initialized before EEPROM + // (because EEPROM code calls the UI). + SETUP_RUN(ui.init()); SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.) From 00d35ccc1453f41060ecc2c24938b9c08f68acdf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Apr 2020 14:54:39 -0500 Subject: [PATCH 0231/1454] Add EXPERIMENTAL_SCURVE to AGC test --- buildroot/share/tests/SAMD51_grandcentral_m4-tests | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/tests/SAMD51_grandcentral_m4-tests b/buildroot/share/tests/SAMD51_grandcentral_m4-tests index 3e47afe327..fbaf5fb7e5 100644 --- a/buildroot/share/tests/SAMD51_grandcentral_m4-tests +++ b/buildroot/share/tests/SAMD51_grandcentral_m4-tests @@ -32,7 +32,7 @@ opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_R LONG_FILENAME_HOST_SUPPORT SCROLL_LONG_FILENAMES BABYSTEPPING DOUBLECLICK_FOR_Z_BABYSTEPPING \ MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ - SQUARE_WAVE_STEPPING TMC_DEBUG + SQUARE_WAVE_STEPPING TMC_DEBUG EXPERIMENTAL_SCURVE exec_test $1 $2 "Build Grand Central M4 Default Configuration" # clean up From 8a9c14ea1d3c39e803373a4f00d6ab28e4a6b6b2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Apr 2020 14:55:16 -0500 Subject: [PATCH 0232/1454] Remove obsolete comment --- Marlin/Configuration_adv.h | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e73964e245..96eff59619 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1535,7 +1535,6 @@ * print acceleration will be reduced during the affected moves to keep within the limit. * * See https://marlinfw.org/docs/features/lin_advance.html for full instructions. - * Mention @Sebastianv650 on GitHub to alert the author of any issues. */ //#define LIN_ADVANCE #if ENABLED(LIN_ADVANCE) From 33bb7859d446a42d699761f6b5c0a449b40a7d35 Mon Sep 17 00:00:00 2001 From: Bob Kuhn Date: Wed, 22 Apr 2020 15:00:10 -0500 Subject: [PATCH 0233/1454] Composite USB for STM32 SDIO (experimental) (#17222) --- .../src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 405 +++++++++--------- .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 1 + platformio.ini | 5 +- 3 files changed, 214 insertions(+), 197 deletions(-) diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index ebe15f9391..3d8e560196 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -27,248 +27,263 @@ #include #include -//#include "SdMscDriver.h" - -//#include "usbd_msc_bot.h" -//#include "usbd_msc_scsi.h" -//#include "usbd_msc_composite.h" -//#include "usbd_msc_cdc_composite.h" - -//#include "usbd_msc_data.h" - -#if defined(STM32F103xE) || defined(STM32F103xG) - #include - #include -#elif defined(STM32F4xx) - #include - #include - #include - #include -#elif defined(STM32F7xx) - #include - #include - #include - #include -#else +#if NONE(STM32F103xE, STM32F103xG, STM32F4xx, STM32F7xx) #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported" #endif -SD_HandleTypeDef hsd; // create SDIO structure +#ifdef USBD_USE_CDC_COMPOSITE -#define TRANSFER_CLOCK_DIV ((uint8_t)SDIO_INIT_CLK_DIV/40) + // use USB drivers -#ifndef USBD_OK - #define USBD_OK 0 -#endif + extern "C" { int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); + int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); + extern SD_HandleTypeDef hsd; + } -void go_to_transfer_speed() { + bool SDIO_Init() { + if (hsd.State == HAL_SD_STATE_READY) return 1; // return passing status + return 0; // return failing status + } - SD_InitTypeDef Init; + bool SDIO_ReadBlock(uint32_t block, uint8_t *src) { + int8_t status = SD_MSC_Read(0, (uint8_t*)src, block, 1); // read one 512 byte block + return (bool) status; + } - /* Default SDIO peripheral configuration for SD card initialization */ - Init.ClockEdge = hsd.Init.ClockEdge; - Init.ClockBypass = hsd.Init.ClockBypass; - Init.ClockPowerSave = hsd.Init.ClockPowerSave; - Init.BusWide = hsd.Init.BusWide; - Init.HardwareFlowControl = hsd.Init.HardwareFlowControl; - Init.ClockDiv = TRANSFER_CLOCK_DIV; + bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + int8_t status = SD_MSC_Write(0, (uint8_t*)src, block, 1); // write one 512 byte block + return (bool) status; + } - /* Initialize SDIO peripheral interface with default configuration */ - SDIO_Init(hsd.Instance, Init); -} +#else // !USBD_USE_CDC_COMPOSITE -void SD_LowLevel_Init(void) { + // use local drivers - uint32_t tempreg; + #if defined(STM32F103xE) || defined(STM32F103xG) + #include + #include + #elif defined(STM32F4xx) + #include + #include + #include + #include + #elif defined(STM32F7xx) + #include + #include + #include + #include + #else + #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported" + #endif - GPIO_InitTypeDef GPIO_InitStruct; + SD_HandleTypeDef hsd; // create SDIO structure - __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks - __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks + #define TRANSFER_CLOCK_DIV (uint8_t(SDIO_INIT_CLK_DIV) / 40) - GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + #ifndef USBD_OK + #define USBD_OK 0 + #endif - #if defined(SDIO_D1_PIN) && defined(SDIO_D2_PIN) && defined(SDIO_D3_PIN) // define D1-D3 only if have a four bit wide SDIO bus - GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3 + void go_to_transfer_speed() { + SD_InitTypeDef Init; + + /* Default SDIO peripheral configuration for SD card initialization */ + Init.ClockEdge = hsd.Init.ClockEdge; + Init.ClockBypass = hsd.Init.ClockBypass; + Init.ClockPowerSave = hsd.Init.ClockPowerSave; + Init.BusWide = hsd.Init.BusWide; + Init.HardwareFlowControl = hsd.Init.HardwareFlowControl; + Init.ClockDiv = TRANSFER_CLOCK_DIV; + + /* Initialize SDIO peripheral interface with default configuration */ + SDIO_Init(hsd.Instance, Init); + } + + void SD_LowLevel_Init(void) { + uint32_t tempreg; + + GPIO_InitTypeDef GPIO_InitStruct; + + __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks + __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks + + GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - #endif - // Configure PD.02 CMD line - GPIO_InitStruct.Pin = GPIO_PIN_2; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus + GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3 + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = 1; // GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + #endif - RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset - RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock + // Configure PD.02 CMD line + GPIO_InitStruct.Pin = GPIO_PIN_2; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - // Enable the DMA2 Clock + RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset + RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock - //Initialize the SDIO (with initial <400Khz Clock) - tempreg = 0; //Reset value - tempreg |= SDIO_CLKCR_CLKEN; //Clock is enabled - tempreg |= (uint32_t)0x76; //Clock Divider. Clock = 48000/(118+2) = 400Khz - //Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable - SDIO->CLKCR = tempreg; + // Enable the DMA2 Clock - //Power up the SDIO - SDIO->POWER = 0x03; -} + //Initialize the SDIO (with initial <400Khz Clock) + tempreg = 0; //Reset value + tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled + tempreg |= (uint32_t)0x76; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz + // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable + SDIO->CLKCR = tempreg; - -void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init - UNUSED(hsd); /* Prevent unused argument(s) compilation warning */ - __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock -} - -constexpr uint8_t SD_RETRY_COUNT = (1 - #if ENABLED(SD_CHECK_AND_RETRY) - + 2 - #endif -); - -bool SDIO_Init() { - //init SDIO and get SD card info - - uint8_t retryCnt = SD_RETRY_COUNT; - - bool status; - hsd.Instance = SDIO; - hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET - SD_LowLevel_Init(); - - uint8_t retry_Cnt = retryCnt; - for (;;) { - status = (bool) HAL_SD_Init(&hsd); - if (!status) break; - if (!--retry_Cnt) return false; // return failing status if retries are exhausted + // Power up the SDIO + SDIO->POWER = 0x03; } - go_to_transfer_speed(); + void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init + UNUSED(hsd); /* Prevent unused argument(s) compilation warning */ + __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock + } - #if defined(SDIO_D1_PIN) && defined(SDIO_D2_PIN) && defined(SDIO_D3_PIN) // go to 4 bit wide mode if pins are defined - retry_Cnt = retryCnt; + constexpr uint8_t SD_RETRY_COUNT = 1 + 2 * ENABLED(SD_CHECK_AND_RETRY); + + bool SDIO_Init() { + //init SDIO and get SD card info + + uint8_t retryCnt = SD_RETRY_COUNT; + + bool status; + hsd.Instance = SDIO; + hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET + SD_LowLevel_Init(); + + uint8_t retry_Cnt = retryCnt; for (;;) { - if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required - if (!--retry_Cnt) break; + status = (bool) HAL_SD_Init(&hsd); + if (!status) break; + if (!--retry_Cnt) return false; // return failing status if retries are exhausted } - if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode - hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET - SD_LowLevel_Init(); + + go_to_transfer_speed(); + + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined retry_Cnt = retryCnt; for (;;) { - status = (bool) HAL_SD_Init(&hsd); - if (!status) break; - if (!--retry_Cnt) return false; // return failing status if retries are exhausted + if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required + if (!--retry_Cnt) break; } + if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode + hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET + SD_LowLevel_Init(); + retry_Cnt = retryCnt; + for (;;) { + status = (bool) HAL_SD_Init(&hsd); + if (!status) break; + if (!--retry_Cnt) return false; // return failing status if retries are exhausted + } + } + #endif + + return true; + } + + void init_SDIO_pins(void) { + GPIO_InitTypeDef GPIO_InitStruct = {0}; + + /**SDIO GPIO Configuration + PC8 ------> SDIO_D0 + PC12 ------> SDIO_CK + PD2 ------> SDIO_CMD + */ + GPIO_InitStruct.Pin = GPIO_PIN_8; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_12; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_2; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + } + + //bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);} + //bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);} + + bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + hsd.Instance = SDIO; + uint8_t retryCnt = SD_RETRY_COUNT; + + bool status; + for (;;) { + status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout + status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK + if (!status) break; // return passing status + if (!--retryCnt) break; // return failing status if retries are exhausted } - #endif + return status; - return true; -} + /* + return (bool) ((status_read | status_card) ? 1 : 0); -void init_SDIO_pins(void) { - GPIO_InitTypeDef GPIO_InitStruct = {0}; + if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false; + if (blockAddress >= SdCard.LogBlockNbr) return false; + if ((0x03 & (uint32_t)data)) return false; // misaligned data - /**SDIO GPIO Configuration - PC8 ------> SDIO_D0 - PC12 ------> SDIO_CK - PD2 ------> SDIO_CMD - */ - GPIO_InitStruct.Pin = GPIO_PIN_8; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; } - GPIO_InitStruct.Pin = GPIO_PIN_12; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + if (!SDIO_CmdReadSingleBlock(blockAddress)) { + SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS); + dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL); + return false; + } - GPIO_InitStruct.Pin = GPIO_PIN_2; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); -} + while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {} -//bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);} -//bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);} - -bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { - bool status; - - hsd.Instance = SDIO; - - uint8_t retryCnt = SD_RETRY_COUNT; - - for (;;) { - bool status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout - status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK - if (!status) return false; // return passing status - if (!--retryCnt) return true; // return failing status if retries are exhausted - } - - /* - return (bool) ((status_read | status_card) ? 1 : 0); - - if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false; - if (blockAddress >= SdCard.LogBlockNbr) return false; - if ((0x03 & (uint32_t)data)) return false; // misaligned data - - if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; } - - if (!SDIO_CmdReadSingleBlock(blockAddress)) { - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS); dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL); - return false; - } - while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {} + if (SDIO->STA & SDIO_STA_RXDAVL) { + while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO; + SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); + return false; + } - dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL); - - if (SDIO->STA & SDIO_STA_RXDAVL) { - while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO; + if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) { + SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); + return false; + } SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); - return false; + */ + + return true; } - if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) { - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); - return false; + bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + hsd.Instance = SDIO; + uint8_t retryCnt = SD_RETRY_COUNT; + + bool status; + for (;;) { + status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout + status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK + if (!status) break; // return passing status + if (!--retryCnt) break; // return failing status if retries are exhausted + } + return status; } - SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); - */ - - return true; -} - -bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { - bool status; - - hsd.Instance = SDIO; - - uint8_t retryCnt = SD_RETRY_COUNT; - - for (;;) { - status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout - status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK - if (!status) return (bool) status; // return passing status - if (!--retryCnt) return (bool) status; // return failing status if retries are exhausted - } -} +#endif // !USBD_USE_CDC_COMPOSITE #endif // SDIO_SUPPORT diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 40b00bcc40..e9ae3f5704 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -247,6 +247,7 @@ #ifndef SDIO_SUPPORT #define SOFTWARE_SPI // Use soft SPI for onboard SD + #undef SDSS #define SDSS SDIO_D3_PIN #define SCK_PIN SDIO_CK_PIN #define MISO_PIN SDIO_D0_PIN diff --git a/platformio.ini b/platformio.ini index d4c56876fc..9a6dbad1f1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -646,7 +646,7 @@ platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" - -DDISABLE_GENERIC_SERIALUSB + -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -704,7 +704,8 @@ platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\" - -IMarlin/src/HAL/STM32 + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial From fd453d23b966a27935b938e7fb0dfa537a505b6e Mon Sep 17 00:00:00 2001 From: Flo082002 Date: Wed, 22 Apr 2020 22:01:19 +0200 Subject: [PATCH 0234/1454] Update German language (#17591) --- Marlin/src/lcd/language/language_de.h | 22 ++++++++++++++++++++-- 1 file changed, 20 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 9f874e979d..4d0516e8d6 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -80,6 +80,7 @@ namespace Language_de { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = PREHEAT_2_LABEL _UxGT(" Einstellungen"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("benutzerdef. Heizen"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Abkühlen"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenz"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser aus"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser an"); @@ -148,8 +149,8 @@ namespace Language_de { PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = PREHEAT_1_LABEL _UxGT(" Netz validieren"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = PREHEAT_2_LABEL _UxGT(" Netz validieren"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Eig. Netz validieren"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Heating Nozzle"); PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 heizt Bett"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Düse aufheizen"); PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Feste Länge Prime"); PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Priming fertig"); PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 abgebrochen"); @@ -229,10 +230,13 @@ namespace Language_de { PROGMEM Language_Str MSG_BED_Z = _UxGT("Bett Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Düse ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Düse geparkt"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düsen-Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Bett"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Gehäuse"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Lüfter"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Lüfter ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Gespeich. Lüfter ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Geschw. Extralüfter"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Geschw. Extralüfter ~"); PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Lüfter Kontroller"); @@ -296,6 +300,7 @@ namespace Language_de { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Konfig. laden"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Standardwerte laden"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Werkseinstellungen"); + PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Einstell. gespei."); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("FW Update vom Medium"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Drucker neustarten"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aktualisieren"); @@ -310,9 +315,13 @@ namespace Language_de { PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reseten"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Abbrechen"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fertig"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Zurück"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Pause..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("SD-Druck pausieren"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("SD-Druck fortsetzen"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("SD-Druck abbrechen"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objekt abbrechen"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Wiederh. n. Stroma."); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Druck vom Medium"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Kein Medium"); @@ -321,6 +330,7 @@ namespace Language_de { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Druck pausiert..."); PROGMEM Language_Str MSG_PRINTING = _UxGT("Druckt..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Druck abgebrochen"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Druck fertig"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Motoren angeschaltet"); PROGMEM Language_Str MSG_KILLED = _UxGT("ABGEBROCHEN"); PROGMEM Language_Str MSG_STOPPED = _UxGT("ANGEHALTEN"); @@ -339,7 +349,7 @@ namespace Language_de { PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z anheben"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prime-Geschwin."); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Einzug-Geschwin."); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düsen-Standby"); + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Filament wechseln"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Filament wechseln *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Filament laden"); @@ -373,6 +383,9 @@ namespace Language_de { PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Sonde ausfahren"); PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Sonde einfahren"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Vorher %s%s%s homen"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Sondenversatz"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Sondenversatz X"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Sondenversatz Y"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Sondenversatz Z"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); @@ -560,4 +573,9 @@ namespace Language_de { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrektur"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto. Kalibiren"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heizung Timeout"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Erneut aufheizen"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Erneut aufhei. ..."); } From 88bdd26c9998dc7524371f02660e76f778091d73 Mon Sep 17 00:00:00 2001 From: Bob Kuhn Date: Wed, 22 Apr 2020 15:04:21 -0500 Subject: [PATCH 0235/1454] Clean up SKR Pro v1.1 pins (#17653) --- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 84b9796774..f9e43c0043 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -218,7 +218,7 @@ #define FAN2_PIN PE6 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN PC9 + #define E0_AUTO_FAN_PIN FAN1_PIN #endif // @@ -344,7 +344,7 @@ *  ̄ ̄ * W1 */ -#define ESP_WIFI_MODULE_COM 6 // must also set SERIAL_PORT or SERIAL_PORT_2 to this -#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE //115200 // use BAUDRATE ? would guarantee same baud rate as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_COM 6 // Must also set SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 #define ESP_WIFI_MODULE_RESET_PIN -1 #define ESP_WIFI_MODULE_ENABLE_PIN PG1 From 6d90d1e1f552dca5e21bc61b676b8e8ce731b280 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Apr 2020 16:35:03 -0500 Subject: [PATCH 0236/1454] Apply TERN to compact code (#17619) --- Marlin/src/HAL/DUE/MarlinSerialUSB.cpp | 8 +- Marlin/src/HAL/DUE/endstop_interrupts.h | 56 +-- Marlin/src/HAL/DUE/fastio.h | 2 +- Marlin/src/HAL/ESP32/HAL.cpp | 52 +-- Marlin/src/HAL/ESP32/Servo.cpp | 4 +- Marlin/src/HAL/ESP32/endstop_interrupts.h | 56 +-- Marlin/src/HAL/HAL.h | 4 +- Marlin/src/HAL/LPC1768/DebugMonitor.cpp | 6 +- Marlin/src/HAL/LPC1768/HAL.cpp | 4 +- Marlin/src/HAL/LPC1768/MarlinSerial.h | 5 +- Marlin/src/HAL/LPC1768/Servo.h | 4 +- Marlin/src/HAL/SAMD51/HAL.cpp | 97 ++--- Marlin/src/HAL/STM32/HAL.cpp | 12 +- .../src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 2 +- Marlin/src/HAL/STM32/Servo.cpp | 4 +- Marlin/src/HAL/STM32/endstop_interrupts.h | 57 +-- Marlin/src/HAL/STM32F1/Servo.cpp | 4 +- Marlin/src/HAL/STM32F1/endstop_interrupts.h | 57 +-- Marlin/src/HAL/STM32_F4_F7/Servo.cpp | 4 +- .../src/HAL/STM32_F4_F7/endstop_interrupts.h | 57 +-- Marlin/src/HAL/TEENSY31_32/Servo.cpp | 4 +- .../src/HAL/TEENSY31_32/endstop_interrupts.h | 44 +-- Marlin/src/HAL/TEENSY35_36/Servo.cpp | 4 +- .../src/HAL/TEENSY35_36/endstop_interrupts.h | 56 +-- Marlin/src/HAL/shared/servo.cpp | 4 +- Marlin/src/MarlinCore.cpp | 110 ++---- Marlin/src/core/drivers.h | 9 +- Marlin/src/core/utility.cpp | 32 +- Marlin/src/feature/babystep.cpp | 13 +- Marlin/src/feature/babystep.h | 7 +- Marlin/src/feature/backlash.h | 22 +- Marlin/src/feature/bedlevel/abl/abl.cpp | 8 +- Marlin/src/feature/bedlevel/bedlevel.cpp | 8 +- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 4 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 140 ++------ Marlin/src/feature/binary_protocol.h | 12 +- Marlin/src/feature/bltouch.cpp | 4 +- Marlin/src/feature/controllerfan.cpp | 7 +- Marlin/src/feature/controllerfan.h | 6 +- Marlin/src/feature/encoder_i2c.cpp | 4 +- Marlin/src/feature/fwretract.cpp | 16 +- Marlin/src/feature/host_actions.cpp | 10 +- Marlin/src/feature/joystick.cpp | 4 +- Marlin/src/feature/joystick.h | 16 +- Marlin/src/feature/leds/leds.cpp | 16 +- Marlin/src/feature/leds/leds.h | 8 +- Marlin/src/feature/leds/neopixel.h | 23 +- .../src/feature/leds/printer_event_leds.cpp | 8 +- Marlin/src/feature/leds/tempstat.cpp | 5 +- Marlin/src/feature/mixing.cpp | 12 +- Marlin/src/feature/mixing.h | 38 +- Marlin/src/feature/mmu2/mmu2.cpp | 8 +- Marlin/src/feature/pause.cpp | 107 ++---- Marlin/src/feature/power.cpp | 14 +- Marlin/src/feature/powerloss.cpp | 40 +-- Marlin/src/feature/probe_temp_comp.h | 4 +- Marlin/src/feature/runout.cpp | 8 +- Marlin/src/feature/spindle_laser.cpp | 8 +- Marlin/src/feature/spindle_laser.h | 4 +- Marlin/src/feature/tmc_util.cpp | 18 +- Marlin/src/feature/tmc_util.h | 40 +-- Marlin/src/gcode/bedlevel/G26.cpp | 41 +-- Marlin/src/gcode/bedlevel/M420.cpp | 16 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 72 +--- Marlin/src/gcode/bedlevel/abl/M421.cpp | 8 +- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 16 +- Marlin/src/gcode/bedlevel/ubl/M421.cpp | 4 +- Marlin/src/gcode/calibrate/G28.cpp | 68 +--- Marlin/src/gcode/calibrate/G33.cpp | 33 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 28 +- Marlin/src/gcode/calibrate/G425.cpp | 50 +-- Marlin/src/gcode/calibrate/G76_M871.cpp | 16 +- Marlin/src/gcode/calibrate/M48.cpp | 4 +- Marlin/src/gcode/config/M200-M205.cpp | 4 +- Marlin/src/gcode/config/M43.cpp | 12 +- Marlin/src/gcode/control/M108_M112_M410.cpp | 4 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 8 +- .../src/gcode/feature/digipot/M907-M910.cpp | 8 +- Marlin/src/gcode/feature/pause/M125.cpp | 25 +- Marlin/src/gcode/feature/pause/M600.cpp | 16 +- Marlin/src/gcode/feature/pause/M701_M702.cpp | 24 +- Marlin/src/gcode/feature/powerloss/M1000.cpp | 4 +- Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/gcode/gcode.h | 276 ++++---------- Marlin/src/gcode/host/M114.cpp | 4 +- Marlin/src/gcode/host/M115.cpp | 10 +- Marlin/src/gcode/lcd/M0_M1.cpp | 8 +- Marlin/src/gcode/motion/G2_G3.cpp | 23 +- Marlin/src/gcode/parser.cpp | 29 +- Marlin/src/gcode/probe/G30.cpp | 4 +- Marlin/src/gcode/probe/M951.cpp | 8 +- Marlin/src/gcode/queue.cpp | 12 +- Marlin/src/gcode/sd/M1001.cpp | 20 +- Marlin/src/gcode/sd/M23.cpp | 4 +- Marlin/src/gcode/sd/M24_M25.cpp | 12 +- Marlin/src/gcode/temp/M104_M109.cpp | 8 +- Marlin/src/gcode/temp/M140_M190.cpp | 4 +- Marlin/src/gcode/temp/M141_M191.cpp | 4 +- Marlin/src/gcode/temp/M303.cpp | 4 +- Marlin/src/inc/Conditionals_LCD.h | 4 +- Marlin/src/inc/Conditionals_post.h | 85 +++-- Marlin/src/inc/SanityCheck.h | 4 + Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 58 +-- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 46 ++- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 20 +- .../lcd/dogm/status_screen_lite_ST7920.cpp | 54 +-- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 22 +- Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 21 +- .../archim2-flash/flash_storage.cpp | 8 +- .../ftdi_eve_lib/basic/commands.cpp | 26 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 60 +++- .../ftdi_eve_touch_ui/screens/base_screen.cpp | 4 +- .../screens/bio_status_screen.cpp | 30 +- .../screens/bio_tune_menu.cpp | 6 +- .../screens/files_screen.cpp | 6 +- .../screens/interface_settings_screen.cpp | 4 +- .../screens/temperature_screen.cpp | 8 +- Marlin/src/lcd/extui/ui_api.cpp | 80 ++--- Marlin/src/lcd/extui_dgus_lcd.cpp | 18 +- Marlin/src/lcd/menu/game/game.h | 16 +- Marlin/src/lcd/menu/menu.cpp | 44 +-- Marlin/src/lcd/menu/menu_advanced.cpp | 8 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 10 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 4 +- Marlin/src/lcd/menu/menu_cancelobject.cpp | 4 +- Marlin/src/lcd/menu/menu_configuration.cpp | 4 +- Marlin/src/lcd/menu/menu_custom.cpp | 4 +- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 12 +- Marlin/src/lcd/menu/menu_main.cpp | 17 +- Marlin/src/lcd/menu/menu_media.cpp | 4 +- Marlin/src/lcd/menu/menu_mixer.cpp | 16 +- Marlin/src/lcd/menu/menu_motion.cpp | 42 +-- Marlin/src/lcd/menu/menu_temperature.cpp | 12 +- Marlin/src/lcd/menu/menu_tune.cpp | 14 +- Marlin/src/lcd/menu/menu_ubl.cpp | 4 +- Marlin/src/lcd/ultralcd.cpp | 115 ++---- Marlin/src/lcd/ultralcd.h | 38 +- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 4 +- Marlin/src/libs/nozzle.cpp | 31 +- Marlin/src/libs/stopwatch.cpp | 32 +- Marlin/src/libs/stopwatch.h | 4 + Marlin/src/module/configuration_store.cpp | 204 +++-------- Marlin/src/module/configuration_store.h | 4 +- Marlin/src/module/delta.cpp | 6 +- Marlin/src/module/endstops.cpp | 63 +--- Marlin/src/module/endstops.h | 18 +- Marlin/src/module/motion.cpp | 135 ++----- Marlin/src/module/motion.h | 10 +- Marlin/src/module/planner.cpp | 217 +++-------- Marlin/src/module/planner.h | 42 +-- Marlin/src/module/printcounter.cpp | 41 +-- Marlin/src/module/probe.cpp | 68 +--- Marlin/src/module/servo.cpp | 4 +- Marlin/src/module/stepper.cpp | 206 +++++------ Marlin/src/module/stepper/indirection.cpp | 14 +- Marlin/src/module/stepper/trinamic.cpp | 33 +- Marlin/src/module/temperature.cpp | 336 +++++------------- Marlin/src/module/temperature.h | 132 ++----- Marlin/src/module/tool_change.cpp | 63 +--- Marlin/src/module/tool_change.h | 12 +- Marlin/src/sd/cardreader.cpp | 107 ++---- Marlin/src/sd/cardreader.h | 10 +- 162 files changed, 1493 insertions(+), 3530 deletions(-) diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index 7a020bbaf0..d267422813 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -73,9 +73,7 @@ int MarlinSerialUSB::peek() { pending_char = udi_cdc_getc(); - #if ENABLED(EMERGENCY_PARSER) - emergency_parser.update(emergency_state, (char)pending_char); - #endif + TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)pending_char)); return pending_char; } @@ -97,9 +95,7 @@ int MarlinSerialUSB::read() { int c = udi_cdc_getc(); - #if ENABLED(EMERGENCY_PARSER) - emergency_parser.update(emergency_state, (char)c); - #endif + TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)c)); return c; } diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h index f81d9055d5..759fefae29 100644 --- a/Marlin/src/HAL/DUE/endstop_interrupts.h +++ b/Marlin/src/HAL/DUE/endstop_interrupts.h @@ -47,43 +47,21 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - #if HAS_X_MAX - _ATTACH(X_MAX_PIN); - #endif - #if HAS_X_MIN - _ATTACH(X_MIN_PIN); - #endif - #if HAS_Y_MAX - _ATTACH(Y_MAX_PIN); - #endif - #if HAS_Y_MIN - _ATTACH(Y_MIN_PIN); - #endif - #if HAS_Z_MAX - _ATTACH(Z_MAX_PIN); - #endif - #if HAS_Z_MIN - _ATTACH(Z_MIN_PIN); - #endif - #if HAS_Z2_MAX - _ATTACH(Z2_MAX_PIN); - #endif - #if HAS_Z2_MIN - _ATTACH(Z2_MIN_PIN); - #endif - #if HAS_Z3_MAX - _ATTACH(Z3_MAX_PIN); - #endif - #if HAS_Z3_MIN - _ATTACH(Z3_MIN_PIN); - #endif - #if HAS_Z4_MAX - _ATTACH(Z4_MAX_PIN); - #endif - #if HAS_Z4_MIN - _ATTACH(Z4_MIN_PIN); - #endif - #if HAS_Z_MIN_PROBE_PIN - _ATTACH(Z_MIN_PROBE_PIN); - #endif + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index 01abd82049..8f4b5a9e2f 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -174,7 +174,7 @@ #define IS_OUTPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) != 0) // Shorthand -#define OUT_WRITE(IO,V) { SET_OUTPUT(IO); WRITE(IO,V); } +#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0) // digitalRead/Write wrappers #define extDigitalRead(IO) digitalRead(IO) diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index d9afa13ab8..641925a294 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -97,9 +97,7 @@ void HAL_init_board() { esp3dlib.init(); #elif ENABLED(WIFISUPPORT) wifi_init(); - #if ENABLED(OTASUPPORT) - OTA_init(); - #endif + TERN_(OTASUPPORT, OTA_init()); #if ENABLED(WEBSUPPORT) spiffs_init(); web_init(); @@ -133,9 +131,7 @@ void HAL_idletask() { #if BOTH(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif - #if ENABLED(ESP3D_WIFISUPPORT) - esp3dlib.idletask(); - #endif + TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); } void HAL_clear_reset_source() { } @@ -176,39 +172,17 @@ void HAL_adc_init() { adc1_config_width(ADC_WIDTH_12Bit); // Configure channels only if used as (re-)configuring a pin for ADC that is used elsewhere might have adverse effects - #if HAS_TEMP_ADC_0 - adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_1 - adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_2 - adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_3 - adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_4 - adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_5 - adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_6 - adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_ADC_7 - adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db); - #endif - #if HAS_HEATED_BED - adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db); - #endif - #if HAS_TEMP_CHAMBER - adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db); - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db); - #endif + TERN_(HAS_TEMP_ADC_0, adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_1, adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_2, adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_3, adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_4, adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db)); + TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db)); + TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db)); // Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail. // That's why we're not setting it up here. diff --git a/Marlin/src/HAL/ESP32/Servo.cpp b/Marlin/src/HAL/ESP32/Servo.cpp index 68ee3d9098..f0a8658562 100644 --- a/Marlin/src/HAL/ESP32/Servo.cpp +++ b/Marlin/src/HAL/ESP32/Servo.cpp @@ -61,9 +61,7 @@ void Servo::move(const int value) { if (attach(0) >= 0) { write(value); safe_delay(servo_delay[channel]); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } #endif // HAS_SERVOS diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h index 2da1cc7477..8738c409b3 100644 --- a/Marlin/src/HAL/ESP32/endstop_interrupts.h +++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h @@ -42,43 +42,21 @@ void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - #if HAS_X_MAX - _ATTACH(X_MAX_PIN); - #endif - #if HAS_X_MIN - _ATTACH(X_MIN_PIN); - #endif - #if HAS_Y_MAX - _ATTACH(Y_MAX_PIN); - #endif - #if HAS_Y_MIN - _ATTACH(Y_MIN_PIN); - #endif - #if HAS_Z_MAX - _ATTACH(Z_MAX_PIN); - #endif - #if HAS_Z_MIN - _ATTACH(Z_MIN_PIN); - #endif - #if HAS_Z2_MAX - _ATTACH(Z2_MAX_PIN); - #endif - #if HAS_Z2_MIN - _ATTACH(Z2_MIN_PIN); - #endif - #if HAS_Z3_MAX - _ATTACH(Z3_MAX_PIN); - #endif - #if HAS_Z3_MIN - _ATTACH(Z3_MIN_PIN); - #endif - #if HAS_Z4_MAX - _ATTACH(Z4_MAX_PIN); - #endif - #if HAS_Z4_MIN - _ATTACH(Z4_MIN_PIN); - #endif - #if HAS_Z_MIN_PROBE_PIN - _ATTACH(Z_MIN_PROBE_PIN); - #endif + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index fa2782cfcb..2e024878ff 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -28,7 +28,5 @@ #define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION) inline void watchdog_refresh() { - #if ENABLED(USE_WATCHDOG) - HAL_watchdog_refresh(); - #endif + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); } diff --git a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp index 2a39e56168..ce9ffec70c 100644 --- a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp +++ b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp @@ -211,11 +211,7 @@ void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause // Nothing below here is compiled because NVIC_SystemReset loops forever - for (;;) { - #if ENABLED(USE_WATCHDOG) - watchdog_init(); - #endif - } + for (;;) { TERN_(USE_WATCHDOG, watchdog_init()); } } extern "C" { diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index f206ce7adb..cfa7afd284 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -70,9 +70,7 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { void flashFirmware(const int16_t) { NVIC_SystemReset(); } void HAL_clear_reset_source(void) { - #if ENABLED(USE_WATCHDOG) - watchdog_clear_timeout_flag(); - #endif + TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); } uint8_t HAL_get_reset_source(void) { diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index b6bbf8e453..d9c6302072 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -44,10 +44,9 @@ public: MarlinSerial(LPC_UART_TypeDef *UARTx) : HardwareSerial(UARTx) #if ENABLED(EMERGENCY_PARSER) - , emergency_state(EmergencyParser::State::EP_RESET) + , emergency_state(EmergencyParser::State::EP_RESET) #endif - { - } + { } void end() {} diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index 71e2bb5695..61400c1f03 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -60,9 +60,7 @@ class libServo: public Servo { if (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach write(value); safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index b3a741fe13..ea5ebd6d64 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -29,71 +29,19 @@ // Local defines // ------------------------ -#if HAS_TEMP_ADC_0 - #define GET_TEMP_0_ADC() PIN_TO_ADC(TEMP_0_PIN) -#else - #define GET_TEMP_0_ADC() -1 -#endif -#if HAS_TEMP_ADC_1 - #define GET_TEMP_1_ADC() PIN_TO_ADC(TEMP_1_PIN) -#else - #define GET_TEMP_1_ADC() -1 -#endif -#if HAS_TEMP_ADC_2 - #define GET_TEMP_2_ADC() PIN_TO_ADC(TEMP_2_PIN) -#else - #define GET_TEMP_2_ADC() -1 -#endif -#if HAS_TEMP_ADC_3 - #define GET_TEMP_3_ADC() PIN_TO_ADC(TEMP_3_PIN) -#else - #define GET_TEMP_3_ADC() -1 -#endif -#if HAS_TEMP_ADC_4 - #define GET_TEMP_4_ADC() PIN_TO_ADC(TEMP_4_PIN) -#else - #define GET_TEMP_4_ADC() -1 -#endif -#if HAS_TEMP_ADC_5 - #define GET_TEMP_5_ADC() PIN_TO_ADC(TEMP_5_PIN) -#else - #define GET_TEMP_5_ADC() -1 -#endif -#if HAS_TEMP_ADC_6 - #define GET_TEMP_6_ADC() PIN_TO_ADC(TEMP_6_PIN) -#else - #define GET_TEMP_6_ADC() -1 -#endif -#if HAS_TEMP_ADC_7 - #define GET_TEMP_7_ADC() PIN_TO_ADC(TEMP_7_PIN) -#else - #define GET_TEMP_7_ADC() -1 -#endif -#if HAS_TEMP_PROBE - #define GET_PROBE_ADC() PIN_TO_ADC(TEMP_PROBE_PIN) -#else - #define GET_PROBE_ADC() -1 -#endif -#if HAS_TEMP_ADC_BED - #define GET_BED_ADC() PIN_TO_ADC(TEMP_BED_PIN) -#else - #define GET_BED_ADC() -1 -#endif -#if HAS_TEMP_ADC_CHAMBER - #define GET_CHAMBER_ADC() PIN_TO_ADC(TEMP_CHAMBER_PIN) -#else - #define GET_CHAMBER_ADC() -1 -#endif -#if ENABLED(FILAMENT_WIDTH_SENSOR) - #define GET_FILAMENT_WIDTH_ADC() PIN_TO_ADC(FILWIDTH_PIN) -#else - #define GET_FILAMENT_WIDTH_ADC() -1 -#endif -#if HAS_ADC_BUTTONS - #define GET_BUTTONS_ADC() PIN_TO_ADC(ADC_KEYPAD_PIN) -#else - #define GET_BUTTONS_ADC() -1 -#endif +#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) +#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) +#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) +#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) +#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) +#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) +#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) +#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) +#define GET_PROBE_ADC() TERN(HAS_TEMP_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) +#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) +#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) +#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) +#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) #define IS_ADC_REQUIRED(n) ( \ GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \ @@ -105,21 +53,22 @@ || GET_BUTTONS_ADC() == n \ ) -#define ADC0_IS_REQUIRED IS_ADC_REQUIRED(0) -#define ADC1_IS_REQUIRED IS_ADC_REQUIRED(1) -#define ADC_IS_REQUIRED (ADC0_IS_REQUIRED || ADC1_IS_REQUIRED) -#if ADC0_IS_REQUIRED +#if IS_ADC_REQUIRED(0) + #define ADC0_IS_REQUIRED 1 #define FIRST_ADC 0 #else #define FIRST_ADC 1 #endif -#if ADC1_IS_REQUIRED +#if IS_ADC_REQUIRED(1) + #define ADC1_IS_REQUIRED 1 #define LAST_ADC 1 #else #define LAST_ADC 0 #endif - -#define DMA_IS_REQUIRED ADC_IS_REQUIRED +#if ADC0_IS_REQUIRED || ADC1_IS_REQUIRED + #define ADC_IS_REQUIRED 1 + #define DMA_IS_REQUIRED 1 +#endif // ------------------------ // Types @@ -423,9 +372,7 @@ uint16_t HAL_adc_result; // HAL initialization task void HAL_init() { - #if DMA_IS_REQUIRED - dma_init(); - #endif + TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 602c1b5022..f49856189b 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -76,20 +76,18 @@ void HAL_init() { #endif #if ENABLED(SRAM_EEPROM_EMULATION) - // Enable access to backup SRAM __HAL_RCC_PWR_CLK_ENABLE(); - HAL_PWR_EnableBkUpAccess(); + HAL_PWR_EnableBkUpAccess(); // Enable access to backup SRAM __HAL_RCC_BKPSRAM_CLK_ENABLE(); - - // Enable backup regulator - LL_PWR_EnableBkUpRegulator(); - // Wait until backup regulator is initialized - while (!LL_PWR_IsActiveFlag_BRR()); + LL_PWR_EnableBkUpRegulator(); // Enable backup regulator + while (!LL_PWR_IsActiveFlag_BRR()); // Wait until backup regulator is initialized #endif #if HAS_TMC_SW_SERIAL SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0); #endif + + TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0)); } void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 3d8e560196..90d6108303 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -148,7 +148,7 @@ __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock } - constexpr uint8_t SD_RETRY_COUNT = 1 + 2 * ENABLED(SD_CHECK_AND_RETRY); + constexpr uint8_t SD_RETRY_COUNT = TERN(SD_CHECK_AND_RETRY, 3, 1); bool SDIO_Init() { //init SDIO and get SD card info diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index 2dcadb8876..d192da5d28 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -52,9 +52,7 @@ void libServo::move(const int value) { if (attach(0) >= 0) { write(value); safe_delay(delay); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } #endif // HAS_SERVOS diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index 0b97c3c774..1a8bf1e031 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -28,43 +28,22 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { - #if HAS_X_MAX - attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_X_MIN - attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Y_MAX - attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Y_MIN - attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MAX - attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MIN - attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z2_MAX - attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z2_MIN - attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z3_MAX - attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z3_MIN - attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z4_MAX - attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z4_MIN - attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MIN_PROBE_PIN - attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); - #endif + #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 06abb2c2b9..da0a7cf1be 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -138,9 +138,7 @@ void libServo::move(const int32_t value) { angle = constrain(value, minAngle, maxAngle); servoWrite(pin, US_TO_COMPARE(ANGLE_TO_US(angle))); safe_delay(servo_delay[servoIndex]); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index 246e292983..a4fc208fe0 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -53,43 +53,22 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { - #if HAS_X_MAX - attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it - #endif - #if HAS_X_MIN - attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Y_MAX - attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Y_MIN - attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MAX - attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MIN - attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z2_MAX - attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z2_MIN - attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z3_MAX - attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z3_MIN - attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z4_MAX - attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z4_MIN - attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MIN_PROBE_PIN - attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); - #endif + #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp index e7fb15e6b1..e2b1b9fdac 100644 --- a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp @@ -44,9 +44,7 @@ void libServo::move(const int value) { if (attach(0) >= 0) { write(value); safe_delay(servo_delay[servoIndex]); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } diff --git a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h index 0b97c3c774..1a8bf1e031 100644 --- a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h @@ -28,43 +28,22 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { - #if HAS_X_MAX - attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_X_MIN - attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Y_MAX - attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Y_MIN - attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MAX - attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MIN - attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z2_MAX - attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z2_MIN - attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z3_MAX - attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z3_MIN - attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z4_MAX - attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z4_MIN - attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE); - #endif - #if HAS_Z_MIN_PROBE_PIN - attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); - #endif + #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/TEENSY31_32/Servo.cpp b/Marlin/src/HAL/TEENSY31_32/Servo.cpp index 2b01d3d875..ccff161f47 100644 --- a/Marlin/src/HAL/TEENSY31_32/Servo.cpp +++ b/Marlin/src/HAL/TEENSY31_32/Servo.cpp @@ -46,9 +46,7 @@ void libServo::move(const int value) { if (attach(0) >= 0) { write(value); safe_delay(servo_delay[servoIndex]); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h index 21fea5bd01..759fefae29 100644 --- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h @@ -47,31 +47,21 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - #if HAS_X_MAX - _ATTACH(X_MAX_PIN); - #endif - #if HAS_X_MIN - _ATTACH(X_MIN_PIN); - #endif - #if HAS_Y_MAX - _ATTACH(Y_MAX_PIN); - #endif - #if HAS_Y_MIN - _ATTACH(Y_MIN_PIN); - #endif - #if HAS_Z_MAX - _ATTACH(Z_MAX_PIN); - #endif - #if HAS_Z_MIN - _ATTACH(Z_MIN_PIN); - #endif - #if HAS_Z2_MAX - _ATTACH(Z2_MAX_PIN); - #endif - #if HAS_Z2_MIN - _ATTACH(Z2_MIN_PIN); - #endif - #if HAS_Z_MIN_PROBE_PIN - _ATTACH(Z_MIN_PROBE_PIN); - #endif + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.cpp b/Marlin/src/HAL/TEENSY35_36/Servo.cpp index f2fd5fe7ff..a9cda868ba 100644 --- a/Marlin/src/HAL/TEENSY35_36/Servo.cpp +++ b/Marlin/src/HAL/TEENSY35_36/Servo.cpp @@ -46,9 +46,7 @@ void libServo::move(const int value) { if (attach(0) >= 0) { write(value); safe_delay(servo_delay[servoIndex]); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h index eaaf297ea2..4a219470ec 100644 --- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h @@ -46,43 +46,21 @@ void endstop_ISR() { endstops.update(); } */ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - #if HAS_X_MAX - _ATTACH(X_MAX_PIN); - #endif - #if HAS_X_MIN - _ATTACH(X_MIN_PIN); - #endif - #if HAS_Y_MAX - _ATTACH(Y_MAX_PIN); - #endif - #if HAS_Y_MIN - _ATTACH(Y_MIN_PIN); - #endif - #if HAS_Z_MAX - _ATTACH(Z_MAX_PIN); - #endif - #if HAS_Z_MIN - _ATTACH(Z_MIN_PIN); - #endif - #if HAS_Z2_MAX - _ATTACH(Z2_MAX_PIN); - #endif - #if HAS_Z2_MIN - _ATTACH(Z2_MIN_PIN); - #endif - #if HAS_Z3_MAX - _ATTACH(Z3_MAX_PIN); - #endif - #if HAS_Z3_MIN - _ATTACH(Z3_MIN_PIN); - #endif - #if HAS_Z4_MAX - _ATTACH(Z4_MAX_PIN); - #endif - #if HAS_Z4_MIN - _ATTACH(Z4_MIN_PIN); - #endif - #if HAS_Z_MIN_PROBE_PIN - _ATTACH(Z_MIN_PROBE_PIN); - #endif + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); } diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index 2c3d7bb7d3..923b7336b4 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -150,9 +150,7 @@ void Servo::move(const int value) { if (attach(0) >= 0) { write(value); safe_delay(servo_delay[servoIndex]); - #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) - detach(); - #endif + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 7aff3b5752..d513db668a 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -313,9 +313,7 @@ void enable_e_steppers() { } void enable_all_steppers() { - #if ENABLED(AUTO_POWER_CONTROL) - powerManager.power_on(); - #endif + TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); @@ -359,9 +357,7 @@ void disable_all_steppers() { } void event_probe_recover() { - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR)); #ifdef ACTION_ON_G29_RECOVER host_action(PSTR(ACTION_ON_G29_RECOVER)); #endif @@ -394,12 +390,8 @@ bool printingIsPaused() { void startOrResumeJob() { if (!printingIsPaused()) { - #if ENABLED(CANCEL_OBJECTS) - cancelable.reset(); - #endif - #if ENABLED(LCD_SHOW_E_TOTAL) - e_move_accumulator = 0; - #endif + TERN_(CANCEL_OBJECTS, cancelable.reset()); + TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0); #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) ui.reset_remaining_time(); #endif @@ -410,11 +402,7 @@ void startOrResumeJob() { #if ENABLED(SDSUPPORT) inline void abortSDPrinting() { - card.endFilePrint( - #if SD_RESORT - true - #endif - ); + card.endFilePrint(TERN_(SD_RESORT, true)); queue.clear(); quickstop_stepper(); print_job_timer.stop(); @@ -427,9 +415,7 @@ void startOrResumeJob() { cutter.kill(); // Full cutter shutdown including ISR control #endif wait_for_heatup = false; - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.purge(); - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.purge()); #ifdef EVENT_GCODE_SD_STOP queue.inject_P(PSTR(EVENT_GCODE_SD_STOP)); #endif @@ -534,13 +520,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } #endif - #if ENABLED(USE_CONTROLLER_FAN) - controllerFan.update(); // Check if fan should be turned on to cool stepper drivers down - #endif + TERN_(USE_CONTROLLER_FAN, controllerFan.update()); // Check if fan should be turned on to cool stepper drivers down - #if ENABLED(AUTO_POWER_CONTROL) - powerManager.check(); - #endif + TERN_(AUTO_POWER_CONTROL, powerManager.check()); #if ENABLED(EXTRUDER_RUNOUT_PREVENT) if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP @@ -608,17 +590,11 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } #endif - #if ENABLED(TEMP_STAT_LEDS) - handle_status_leds(); - #endif + TERN_(TEMP_STAT_LEDS, handle_status_leds()); - #if ENABLED(MONITOR_DRIVER_STATUS) - monitor_tmc_drivers(); - #endif + TERN_(MONITOR_DRIVER_STATUS, monitor_tmc_drivers()); - #if ENABLED(MONITOR_L6470_DRIVER_STATUS) - L64xxManager.monitor_driver(); - #endif + TERN_(MONITOR_L6470_DRIVER_STATUS, L64xxManager.monitor_driver()); // Limit check_axes_activity frequency to 10Hz static millis_t next_check_axes_ms = 0; @@ -669,17 +645,13 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { thermalManager.manage_heater(); // Max7219 heartbeat, animation, etc - #if ENABLED(MAX7219_DEBUG) - max7219.idle_tasks(); - #endif + TERN_(MAX7219_DEBUG, max7219.idle_tasks()); // Return if setup() isn't completed if (marlin_state == MF_INITIALIZING) return; // Handle filament runout sensors - #if HAS_FILAMENT_SENSOR - runout.run(); - #endif + TERN_(HAS_FILAMENT_SENSOR, runout.run()); // Run HAL idle tasks #ifdef HAL_IDLETASK @@ -700,29 +672,19 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { #endif // Handle SD Card insert / remove - #if ENABLED(SDSUPPORT) - card.manage_media(); - #endif + TERN_(SDSUPPORT, card.manage_media()); // Handle USB Flash Drive insert / remove - #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - Sd2Card::idle(); - #endif + TERN_(USB_FLASH_DRIVE_SUPPORT, Sd2Card::idle()); // Announce Host Keepalive state (if any) - #if ENABLED(HOST_KEEPALIVE_FEATURE) - gcode.host_keepalive(); - #endif + TERN_(HOST_KEEPALIVE_FEATURE, gcode.host_keepalive()); // Update the Print Job Timer state - #if ENABLED(PRINTCOUNTER) - print_job_timer.tick(); - #endif + TERN_(PRINTCOUNTER, print_job_timer.tick()); // Update the Beeper queue - #if USE_BEEPER - buzzer.tick(); - #endif + TERN_(USE_BEEPER, buzzer.tick()); // Read Buttons and Update the LCD ui.update(); @@ -742,24 +704,16 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { // Auto-report Temperatures / SD Status #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { - #if ENABLED(AUTO_REPORT_TEMPERATURES) - thermalManager.auto_report_temperatures(); - #endif - #if ENABLED(AUTO_REPORT_SD_STATUS) - card.auto_report_sd_status(); - #endif + TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_report_temperatures()); + TERN_(AUTO_REPORT_SD_STATUS, card.auto_report_sd_status()); } #endif // Update the Prusa MMU2 - #if ENABLED(PRUSA_MMU2) - mmu2.mmu_loop(); - #endif + TERN_(PRUSA_MMU2, mmu2.mmu_loop()); // Handle Joystick jogging - #if ENABLED(POLL_JOG) - joystick.inject_jog_moves(); - #endif + TERN_(POLL_JOG, joystick.inject_jog_moves()); } /** @@ -769,9 +723,7 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { thermalManager.disable_all_heaters(); - #if HAS_CUTTER - cutter.kill(); // Full cutter shutdown including ISR control - #endif + TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control SERIAL_ERROR_MSG(STR_ERR_KILLED); @@ -802,20 +754,14 @@ void minkill(const bool steppers_off/*=false*/) { // Reiterate heaters off thermalManager.disable_all_heaters(); - #if HAS_CUTTER - cutter.kill(); // Reiterate cutter shutdown - #endif + TERN_(HAS_CUTTER, cutter.kill()); // Reiterate cutter shutdown // Power off all steppers (for M112) or just the E steppers steppers_off ? disable_all_steppers() : disable_e_steppers(); - #if ENABLED(PSU_CONTROL) - PSU_OFF(); - #endif + TERN_(PSU_CONTROL, PSU_OFF()); - #if HAS_SUICIDE - suicide(); - #endif + TERN_(HAS_SUICIDE, suicide()); #if HAS_KILL @@ -1016,9 +962,7 @@ void setup() { SETUP_RUN(touch.init()); #endif - #if HAS_M206_COMMAND - current_position += home_offset; // Init current position based on home_offset - #endif + TERN_(HAS_M206_COMMAND, current_position += home_offset); // Init current position based on home_offset sync_plan_position(); // Vital to init stepper/planner equivalent for current_position diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 418a24ec92..37654dc11f 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -86,6 +86,10 @@ || AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \ || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) ) +// +// Trinamic Stepper Drivers +// + // Test for supported TMC drivers that require advanced configuration // Does not match standalone configurations #if ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) \ @@ -171,8 +175,9 @@ #define HAS_TMC_SPI 1 #endif -// Defines that can't be evaluated now -#define HAS_TMC_SW_SERIAL ANY_AXIS_HAS(SW_SERIAL) +// +// L64XX Stepper Drivers +// #if HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01) #define HAS_L64XX 1 diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 5e159af581..62e79e42ea 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -57,21 +57,21 @@ void safe_delay(millis_t ms) { void log_machine_info() { SERIAL_ECHOLNPGM("Machine Type: " - TERN(DELTA, "Delta", "") - TERN(IS_SCARA, "SCARA", "") - TERN(IS_CORE, "Core", "") - TERN(IS_CARTESIAN, "Cartesian", "") + TERN_(DELTA, "Delta") + TERN_(IS_SCARA, "SCARA") + TERN_(IS_CORE, "Core") + TERN_(IS_CARTESIAN, "Cartesian") ); SERIAL_ECHOLNPGM("Probe: " - TERN(PROBE_MANUALLY, "PROBE_MANUALLY", "") - TERN(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE", "") - TERN(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE", "") - TERN(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE"), "") - TERN(TOUCH_MI_PROBE, "TOUCH_MI_PROBE", "") - TERN(Z_PROBE_SLED, "Z_PROBE_SLED", "") - TERN(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY", "") - TERN(SOLENOID_PROBE, "SOLENOID_PROBE", "") + TERN_(PROBE_MANUALLY, "PROBE_MANUALLY") + TERN_(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE") + TERN_(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE") + TERN_(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE")) + TERN_(TOUCH_MI_PROBE, "TOUCH_MI_PROBE") + TERN_(Z_PROBE_SLED, "Z_PROBE_SLED") + TERN_(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY") + TERN_(SOLENOID_PROBE, "SOLENOID_PROBE") TERN(PROBE_SELECTED, "", "NONE") ); @@ -108,10 +108,10 @@ void safe_delay(millis_t ms) { #if HAS_ABL_OR_UBL SERIAL_ECHOPGM("Auto Bed Leveling: " - TERN(AUTO_BED_LEVELING_LINEAR, "LINEAR", "") - TERN(AUTO_BED_LEVELING_BILINEAR, "BILINEAR", "") - TERN(AUTO_BED_LEVELING_3POINT, "3POINT", "") - TERN(AUTO_BED_LEVELING_UBL, "UBL", "") + TERN_(AUTO_BED_LEVELING_LINEAR, "LINEAR") + TERN_(AUTO_BED_LEVELING_BILINEAR, "BILINEAR") + TERN_(AUTO_BED_LEVELING_3POINT, "3POINT") + TERN_(AUTO_BED_LEVELING_UBL, "UBL") ); if (planner.leveling_active) { diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index 5d2dc47bee..9c5bba95fc 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -58,9 +58,7 @@ void Babystep::add_steps(const AxisEnum axis, const int16_t distance) { if (DISABLED(BABYSTEP_WITHOUT_HOMING) && !TEST(axis_known_position, axis)) return; accum += distance; // Count up babysteps for the UI - #if ENABLED(BABYSTEP_DISPLAY_TOTAL) - axis_total[BS_TOTAL_IND(axis)] += distance; - #endif + TERN_(BABYSTEP_DISPLAY_TOTAL, axis_total[BS_TOTAL_IND(axis)] += distance); #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE) #define BSA_ENABLE(AXIS) do{ switch (AXIS) { case X_AXIS: ENABLE_AXIS_X(); break; case Y_AXIS: ENABLE_AXIS_Y(); break; case Z_AXIS: ENABLE_AXIS_Z(); break; default: break; } }while(0) @@ -107,13 +105,10 @@ void Babystep::add_steps(const AxisEnum axis, const int16_t distance) { #endif steps[BS_AXIS_IND(axis)] += distance; #endif - #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE) - gcode.reset_stepper_timeout(); - #endif - #if ENABLED(INTEGRATED_BABYSTEPPING) - if (has_steps()) stepper.initiateBabystepping(); - #endif + TERN_(BABYSTEP_ALWAYS_AVAILABLE, gcode.reset_stepper_timeout()); + + TERN_(INTEGRATED_BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping()); } #endif // BABYSTEPPING diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index 287664502c..a10655d45b 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -55,11 +55,8 @@ public: #if ENABLED(BABYSTEP_DISPLAY_TOTAL) static int16_t axis_total[BS_TOTAL_IND(Z_AXIS) + 1]; // Total babysteps since G28 static inline void reset_total(const AxisEnum axis) { - if (true - #if ENABLED(BABYSTEP_XY) - && axis == Z_AXIS - #endif - ) axis_total[BS_TOTAL_IND(axis)] = 0; + if (TERN1(BABYSTEP_XY, axis == Z_AXIS)) + axis_total[BS_TOTAL_IND(axis)] = 0; } #endif diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 20666c540b..bbf4903e8f 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -55,26 +55,16 @@ public: static inline float get_measurement(const AxisEnum a) { // Return the measurement averaged over all readings - return ( - #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - measured_count[a] > 0 ? measured_mm[a] / measured_count[a] : - #endif - 0 + return TERN(MEASURE_BACKLASH_WHEN_PROBING + , measured_count[a] > 0 ? measured_mm[a] / measured_count[a] : 0 + , 0 ); - #if DISABLED(MEASURE_BACKLASH_WHEN_PROBING) - UNUSED(a); - #endif + TERN(MEASURE_BACKLASH_WHEN_PROBING,,UNUSED(a)); } static inline bool has_measurement(const AxisEnum a) { - return (false - #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - || (measured_count[a] > 0) - #endif - ); - #if DISABLED(MEASURE_BACKLASH_WHEN_PROBING) - UNUSED(a); - #endif + return TERN0(MEASURE_BACKLASH_WHEN_PROBING, measured_count[a] > 0); + TERN(MEASURE_BACKLASH_WHEN_PROBING,,UNUSED(a)); } static inline bool has_any_measurement() { diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp index 33c9cbdfde..0ee35fd61c 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.cpp +++ b/Marlin/src/feature/bedlevel/abl/abl.cpp @@ -74,9 +74,7 @@ static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t // Take the average instead of the median z_values[x][y] = (a + b + c) / 3.0; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); // Median is robust (ignores outliers). // z_values[x][y] = (a < b) ? ((b < c) ? b : (c < a) ? a : c) @@ -241,9 +239,7 @@ void print_bilinear_leveling_grid() { // Refresh after other values have been updated void refresh_bed_level() { bilinear_grid_factor = bilinear_grid_spacing.reciprocal(); - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); } #if ENABLED(ABL_BILINEAR_SUBDIVISION) diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 63493712a8..59e0a6fba6 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -145,9 +145,7 @@ void reset_bed_level() { bilinear_grid_spacing.reset(); GRID_LOOP(x, y) { z_values[x][y] = NAN; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, 0); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, 0)); } #elif ABL_PLANAR planner.bed_level_matrix.set_to_identity(); @@ -245,9 +243,7 @@ void reset_bed_level() { current_position = pos; - #if ENABLED(LCD_BED_LEVELING) - ui.wait_for_move = false; - #endif + TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); } #endif diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index cf8e935be9..8d382e8273 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -113,9 +113,7 @@ void unified_bed_leveling::set_all_mesh_points_to_value(const float value) { GRID_LOOP(x, y) { z_values[x][y] = value; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, value); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, value)); } } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 86a08afbff..7d991fcccd 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -305,17 +305,13 @@ const int8_t p_val = parser.intval('P', -1); const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J'); - #if HOTENDS > 1 - const uint8_t old_tool_index = active_extruder; - #endif + TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index = active_extruder); // Check for commands that require the printer to be homed if (may_move) { planner.synchronize(); if (axes_need_homing()) gcode.home_all_axes(); - #if HOTENDS > 1 - if (active_extruder != 0) tool_change(0); - #endif + TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); } // Invalidate Mesh Points. This command is a little bit asymmetrical because @@ -340,9 +336,7 @@ break; // No more invalid Mesh Points to populate } z_values[cpos.x][cpos.y] = NAN; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(cpos, 0.0f); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, 0.0f)); cnt++; } } @@ -369,9 +363,7 @@ const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x, p2 = 0.5f * (GRID_MAX_POINTS_Y) - y; z_values[x][y] += 2.0f * HYPOT(p1, p2); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } break; @@ -392,9 +384,7 @@ for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed z_values[x][y] += parser.seen('C') ? g29_constant : 9.99f; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } break; } @@ -540,9 +530,7 @@ } else { z_values[cpos.x][cpos.y] = g29_constant; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(cpos, g29_constant); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, g29_constant)); } } } @@ -683,9 +671,7 @@ UNUSED(probe_deployed); #endif - #if HOTENDS > 1 - tool_change(old_tool_index); - #endif + TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index)); return; } @@ -718,9 +704,7 @@ GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { z_values[x][y] -= mean + value; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } } @@ -728,9 +712,7 @@ GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { z_values[x][y] += g29_constant; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } } @@ -742,9 +724,7 @@ void unified_bed_leveling::probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) { probe.deploy(); // Deploy before ui.capture() to allow for PAUSE_BEFORE_DEPLOY_STOW - #if HAS_LCD_MENU - ui.capture(); - #endif + TERN_(HAS_LCD_MENU, ui.capture()); save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained uint8_t count = GRID_MAX_POINTS; @@ -755,9 +735,7 @@ const int point_num = (GRID_MAX_POINTS) - count + 1; SERIAL_ECHOLNPAIR("\nProbing mesh point ", point_num, "/", int(GRID_MAX_POINTS), ".\n"); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS)); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); #if HAS_LCD_MENU if (ui.button_pressed()) { @@ -776,9 +754,7 @@ : find_closest_mesh_point_of_type(INVALID, near, true); if (best.pos.x >= 0) { // mesh point found and is reachable by probe - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_START); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_START)); const float measured_z = probe.probe_at_point( best.meshpos(), stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level @@ -793,13 +769,10 @@ } while (best.pos.x >= 0 && --count); - #if HAS_LCD_MENU - ui.release(); - #endif - probe.stow(); // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW - #if HAS_LCD_MENU - ui.capture(); - #endif + // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW + TERN_(HAS_LCD_MENU, ui.release()); + probe.stow(); + TERN_(HAS_LCD_MENU, ui.capture()); #ifdef Z_AFTER_PROBING probe.move_z_after_probing(); @@ -858,9 +831,7 @@ static void echo_and_take_a_measurement() { SERIAL_ECHOLNPGM(" and take a measurement."); } float unified_bed_leveling::measure_business_card_thickness(float in_height) { - #if HAS_LCD_MENU - ui.capture(); - #endif + TERN_(HAS_LCD_MENU, ui.capture()); save_ubl_active_state_and_disable(); // Disable bed level correction for probing do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), in_height); @@ -899,9 +870,7 @@ } void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const float &z_clearance, const float &thick, const bool do_ubl_mesh_map) { - #if HAS_LCD_MENU - ui.capture(); - #endif + TERN_(HAS_LCD_MENU, ui.capture()); save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained do_blocking_move_to_xy_z(current_position, z_clearance); @@ -929,9 +898,7 @@ do_blocking_move_to_z(z_clearance); KEEPALIVE_STATE(PAUSED_FOR_USER); - #if HAS_LCD_MENU - ui.capture(); - #endif + TERN_(HAS_LCD_MENU, ui.capture()); if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing @@ -950,9 +917,7 @@ } z_values[lpos.x][lpos.y] = current_position.z - thick; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y])); if (g29_verbose_level > 2) SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[lpos.x][lpos.y], 6); @@ -998,14 +963,11 @@ save_ubl_active_state_and_disable(); LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); - #if HAS_LCD_MENU - ui.capture(); // Take over control of the LCD encoder - #endif + TERN_(HAS_LCD_MENU, ui.capture()); // Take over control of the LCD encoder + do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance - #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset - #endif + TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset MeshFlags done_flags{0}; const xy_int8_t &lpos = location.pos; @@ -1026,9 +988,7 @@ do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance - #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset before editing - #endif + TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset before editing KEEPALIVE_STATE(PAUSED_FOR_USER); @@ -1044,9 +1004,7 @@ do { new_z = lcd_mesh_edit(); - #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - do_blocking_move_to_z(h_offset + new_z); // Move the nozzle as the point is edited - #endif + TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited idle(); SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } while (!ui.button_pressed()); @@ -1056,9 +1014,7 @@ if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location, new_z); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, new_z)); serial_delay(20); // No switch noise ui.refresh(); @@ -1086,9 +1042,7 @@ bool unified_bed_leveling::g29_parameter_parsing() { bool err_flag = false; - #if HAS_LCD_MENU - set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29)); - #endif + TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29))); g29_constant = 0; g29_repetition_cnt = 0; @@ -1210,9 +1164,7 @@ ubl_state_recursion_chk++; if (ubl_state_recursion_chk != 1) { SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); - #if HAS_LCD_MENU - set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR)); - #endif + TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR))); return; } #endif @@ -1224,9 +1176,7 @@ #if ENABLED(UBL_DEVEL_DEBUGGING) if (--ubl_state_recursion_chk) { SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); - #if HAS_LCD_MENU - set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR)); - #endif + TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR))); return; } #endif @@ -1341,9 +1291,7 @@ const float v2 = z_values[dx + xdir][dy + ydir]; if (!isnan(v2)) { z_values[x][y] = v1 < v2 ? v1 : v1 + v1 - v2; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); return true; } } @@ -1407,9 +1355,7 @@ if (do_3_pt_leveling) { SERIAL_ECHOLNPGM("Tilting mesh (1/3)"); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH)); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); measured_z = probe.probe_at_point(points[0], PROBE_PT_RAISE, g29_verbose_level); if (isnan(measured_z)) @@ -1428,9 +1374,7 @@ if (!abort_flag) { SERIAL_ECHOLNPGM("Tilting mesh (2/3)"); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH)); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); measured_z = probe.probe_at_point(points[1], PROBE_PT_RAISE, g29_verbose_level); #ifdef VALIDATE_MESH_TILT @@ -1450,9 +1394,7 @@ if (!abort_flag) { SERIAL_ECHOLNPGM("Tilting mesh (3/3)"); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH)); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); measured_z = probe.probe_at_point(points[2], PROBE_PT_STOW, g29_verbose_level); #ifdef VALIDATE_MESH_TILT @@ -1495,9 +1437,7 @@ if (!abort_flag) { SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n"); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); measured_z = probe.probe_at_point(rpos, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling @@ -1586,9 +1526,7 @@ } z_values[i][j] = mz - lsf_results.D; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(i, j, z_values[i][j]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, z_values[i][j])); } if (DEBUGGING(LEVELING)) { @@ -1684,9 +1622,7 @@ } const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; z_values[ix][iy] = ez; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); idle(); // housekeeping } } @@ -1826,9 +1762,7 @@ GRID_LOOP(x, y) { z_values[x][y] -= tmp_z_values[x][y]; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } } diff --git a/Marlin/src/feature/binary_protocol.h b/Marlin/src/feature/binary_protocol.h index 978d6a2c02..c7850c4315 100644 --- a/Marlin/src/feature/binary_protocol.h +++ b/Marlin/src/feature/binary_protocol.h @@ -82,9 +82,7 @@ private: } transfer_active = true; data_waiting = 0; - #if ENABLED(BINARY_STREAM_COMPRESSION) - heatshrink_decoder_reset(&hsd); - #endif + TERN_(BINARY_STREAM_COMPRESSION, heatshrink_decoder_reset(&hsd)); return true; } @@ -127,9 +125,7 @@ private: card.closefile(); card.release(); } - #if ENABLED(BINARY_STREAM_COMPRESSION) - heatshrink_decoder_finish(&hsd); - #endif + TERN_(BINARY_STREAM_COMPRESSION, heatshrink_decoder_finish(&hsd)); transfer_active = false; return true; } @@ -139,9 +135,7 @@ private: card.closefile(); card.removeFile(card.filename); card.release(); - #if ENABLED(BINARY_STREAM_COMPRESSION) - heatshrink_decoder_finish(&hsd); - #endif + TERN_(BINARY_STREAM_COMPRESSION, heatshrink_decoder_finish(&hsd)); } transfer_active = false; return; diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index efe575ec63..58b799c70f 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -124,9 +124,7 @@ bool BLTouch::deploy_proc() { } // One of the recommended ANTClabs ways to probe, using SW MODE - #if ENABLED(BLTOUCH_FORCE_SW_MODE) - _set_SW_mode(); - #endif + TERN_(BLTOUCH_FORCE_SW_MODE, _set_SW_mode()); // Now the probe is ready to issue a 10ms pulse when the pin goes up. // The trigger STOW (see motion.cpp for example) will pull up the probes pin as soon as the pulse diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index debfdea1f9..c329acf697 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -81,11 +81,8 @@ void ControllerFan::update() { ; // If any of the drivers or the heated bed are enabled... - if (motor_on - #if HAS_HEATED_BED - || thermalManager.temp_bed.soft_pwm_amount > 0 - #endif - ) lastMotorOn = ms; //... set time to NOW so the fan will turn on + if (motor_on || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0)) + lastMotorOn = ms; //... set time to NOW so the fan will turn on // Fan Settings. Set fan > 0: // - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds. diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index cd56ff8ced..9c544ca1c9 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -62,11 +62,7 @@ class ControllerFan { #endif static inline bool state() { return speed > 0; } static inline void init() { reset(); } - static inline void reset() { - #if ENABLED(CONTROLLER_FAN_EDITABLE) - settings = controllerFan_defaults; - #endif - } + static inline void reset() { TERN_(CONTROLLER_FAN_EDITABLE, settings = controllerFan_defaults); } static void setup(); static void update(); }; diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index a70227a270..dfc29a70d3 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -459,9 +459,7 @@ void I2CPositionEncoder::reset() { Wire.write(I2CPE_RESET_COUNT); Wire.endTransmission(); - #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) - ZERO(err); - #endif + TERN_(I2CPE_ERR_ROLLING_AVERAGE, ZERO(err)); } diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 122e9ae4f7..e1be10d13b 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -60,9 +60,7 @@ float FWRetract::current_retract[EXTRUDERS], // Retract value used by p FWRetract::current_hop; void FWRetract::reset() { - #if ENABLED(FWRETRACT_AUTORETRACT) - autoretract_enabled = false; - #endif + TERN_(FWRETRACT_AUTORETRACT, autoretract_enabled = false); settings.retract_length = RETRACT_LENGTH; settings.retract_feedrate_mm_s = RETRACT_FEEDRATE; settings.retract_zraise = RETRACT_ZRAISE; @@ -128,7 +126,7 @@ void FWRetract::retract(const bool retracting SERIAL_ECHOLNPAIR("current_hop ", current_hop); //*/ - const float base_retract = TERN(RETRACT_SYNC_MIXING, MIXING_STEPPERS, 1) + const float base_retract = TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) * (swapping ? settings.swap_retract_length : settings.retract_length); // The current position will be the destination for E and Z moves @@ -144,7 +142,7 @@ void FWRetract::retract(const bool retracting // Retract by moving from a faux E position back to the current E position current_retract[active_extruder] = base_retract; prepare_internal_move_to_destination( // set current to destination - settings.retract_feedrate_mm_s * TERN(RETRACT_SYNC_MIXING, MIXING_STEPPERS, 1) + settings.retract_feedrate_mm_s * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) ); // Is a Z hop set, and has the hop not yet been done? @@ -170,9 +168,11 @@ void FWRetract::retract(const bool retracting current_retract[active_extruder] = 0; - const feedRate_t fr_mm_s = TERN(RETRACT_SYNC_MIXING, MIXING_STEPPERS, 1) - * (swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s); - prepare_internal_move_to_destination(fr_mm_s); // Recover E, set_current_to_destination + // Recover E, set_current_to_destination + prepare_internal_move_to_destination( + (swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s) + * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) + ); } TERN_(RETRACT_SYNC_MIXING, mixer.T(old_mixing_tool)); // Restore original mixing tool diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 2108f4e7f4..1d199a6fb6 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -108,11 +108,7 @@ void host_action(const char * const pstr, const bool eol) { } void filament_load_host_prompt() { - const bool disable_to_continue = (false - #if HAS_FILAMENT_SENSOR - || runout.filament_ran_out - #endif - ); + const bool disable_to_continue = TERN0(HAS_FILAMENT_SENSOR, runout.filament_ran_out); host_prompt_do(PROMPT_FILAMENT_RUNOUT, PSTR("Paused"), PSTR("PurgeMore"), disable_to_continue ? PSTR("DisableRunout") : CONTINUE_STR ); @@ -160,9 +156,7 @@ void host_action(const char * const pstr, const bool eol) { } break; case PROMPT_USER_CONTINUE: - #if HAS_RESUME_CONTINUE - wait_for_user = false; - #endif + TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); msg = PSTR("FILAMENT_RUNOUT_CONTINUE"); break; case PROMPT_PAUSE_RESUME: diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index 66afb63b05..586b93b8ba 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -154,9 +154,7 @@ Joystick joystick; // Other non-joystick poll-based jogging could be implemented here // with "jogging" encapsulated as a more general class. - #if ENABLED(EXTENSIBLE_UI) - ExtUI::_joystick_update(norm_jog); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::_joystick_update(norm_jog)); // norm_jog values of [-1 .. 1] maps linearly to [-feedrate .. feedrate] xyz_float_t move_dist{0}; diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h index 12f9554a71..e2a8276373 100644 --- a/Marlin/src/feature/joystick.h +++ b/Marlin/src/feature/joystick.h @@ -35,19 +35,11 @@ class Joystick { friend class Temperature; private: - #if HAS_JOY_ADC_X - static temp_info_t x; - #endif - #if HAS_JOY_ADC_Y - static temp_info_t y; - #endif - #if HAS_JOY_ADC_Z - static temp_info_t z; - #endif + TERN_(HAS_JOY_ADC_X, static temp_info_t x); + TERN_(HAS_JOY_ADC_Y, static temp_info_t y); + TERN_(HAS_JOY_ADC_Z, static temp_info_t z); public: - #if ENABLED(JOYSTICK_DEBUG) - static void report(); - #endif + TERN_(JOYSTICK_DEBUG, static void report()); static void calculate(xyz_float_t &norm_jog); static void inject_jog_moves(); }; diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 13d60fd5b7..1cd7bc9821 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -68,15 +68,9 @@ void LEDLights::setup() { if (PWM_PIN(RGB_LED_W_PIN)) SET_PWM(RGB_LED_W_PIN); else SET_OUTPUT(RGB_LED_W_PIN); #endif #endif - #if ENABLED(NEOPIXEL_LED) - neo.init(); - #endif - #if ENABLED(PCA9533) - PCA9533_init(); - #endif - #if ENABLED(LED_USER_PRESET_STARTUP) - set_default(); - #endif + TERN_(NEOPIXEL_LED, neo.init()); + TERN_(PCA9533, PCA9533_init()); + TERN_(LED_USER_PRESET_STARTUP, set_default()); } void LEDLights::set_color(const LEDColor &incol @@ -140,9 +134,7 @@ void LEDLights::set_color(const LEDColor &incol pca9632_set_led_color(incol); #endif - #if ENABLED(PCA9533) - PCA9533_setColor(incol.r, incol.g, incol.b); - #endif + TERN_(PCA9533, PCA9533_setColor(incol.r, incol.g, incol.b)); #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) // Don't update the color when OFF diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index 22184381fc..17bd77eb7f 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -34,7 +34,9 @@ #endif // A white component can be passed -#define HAS_WHITE_LED EITHER(RGBW_LED, NEOPIXEL_LED) +#if EITHER(RGBW_LED, NEOPIXEL_LED) + #define HAS_WHITE_LED 1 +#endif /** * LEDcolor type for use with leds.set_color @@ -85,9 +87,7 @@ typedef struct LEDColor { LEDColor& operator=(const uint8_t (&rgbw)[4]) { r = rgbw[0]; g = rgbw[1]; b = rgbw[2]; - #if HAS_WHITE_LED - w = rgbw[3]; - #endif + TERN_(HAS_WHITE_LED, w = rgbw[3]); return *this; } diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 11e435b830..1b1b74fdfe 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -38,10 +38,15 @@ // Defines // ------------------------ -#define MULTIPLE_NEOPIXEL_TYPES (defined(NEOPIXEL2_TYPE) && (NEOPIXEL2_TYPE != NEOPIXEL_TYPE)) +#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE + #define MULTIPLE_NEOPIXEL_TYPES 1 +#endif -#define NEOPIXEL_IS_RGB (NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR) -#define NEOPIXEL_IS_RGBW !NEOPIXEL_IS_RGB +#if NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR + #define NEOPIXEL_IS_RGB 1 +#else + #define NEOPIXEL_IS_RGBW 1 +#endif #if NEOPIXEL_IS_RGB #define NEO_WHITE 255, 255, 255, 0 @@ -73,23 +78,17 @@ public: static inline void begin() { adaneo1.begin(); - #if MULTIPLE_NEOPIXEL_TYPES - adaneo2.begin(); - #endif + TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.begin()); } static inline void set_pixel_color(const uint16_t n, const uint32_t c) { adaneo1.setPixelColor(n, c); - #if MULTIPLE_NEOPIXEL_TYPES - adaneo2.setPixelColor(n, c); - #endif + TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setPixelColor(n, c)); } static inline void set_brightness(const uint8_t b) { adaneo1.setBrightness(b); - #if MULTIPLE_NEOPIXEL_TYPES - adaneo2.setBrightness(b); - #endif + TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setBrightness(b)); } static inline void show() { diff --git a/Marlin/src/feature/leds/printer_event_leds.cpp b/Marlin/src/feature/leds/printer_event_leds.cpp index 70eee76b30..64b154f557 100644 --- a/Marlin/src/feature/leds/printer_event_leds.cpp +++ b/Marlin/src/feature/leds/printer_event_leds.cpp @@ -47,10 +47,10 @@ PrinterEventLEDs printerEventLEDs; inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b) { leds.set_color( MakeLEDColor(r, g, b, 0, neo.brightness()) - #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) - , true - #endif - ); + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + , true + #endif + ); } #endif diff --git a/Marlin/src/feature/leds/tempstat.cpp b/Marlin/src/feature/leds/tempstat.cpp index 2d7afdcf9e..d3d23a6235 100644 --- a/Marlin/src/feature/leds/tempstat.cpp +++ b/Marlin/src/feature/leds/tempstat.cpp @@ -36,10 +36,7 @@ void handle_status_leds() { static millis_t next_status_led_update_ms = 0; if (ELAPSED(millis(), next_status_led_update_ms)) { next_status_led_update_ms += 500; // Update every 0.5s - float max_temp = 0.0; - #if HAS_HEATED_BED - max_temp = _MAX(thermalManager.degTargetBed(), thermalManager.degBed()); - #endif + float max_temp = TERN0(HAS_HEATED_BED, _MAX(thermalManager.degTargetBed(), thermalManager.degBed())); HOTEND_LOOP() max_temp = _MAX(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e)); const int8_t new_red = (max_temp > 55.0) ? HIGH : (max_temp < 54.0 || old_red < 0) ? LOW : old_red; diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index 5ef0e918f7..28858112d5 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -44,7 +44,7 @@ int_fast8_t Mixer::runner = 0; mixer_comp_t Mixer::s_color[MIXING_STEPPERS]; mixer_accu_t Mixer::accu[MIXING_STEPPERS] = { 0 }; -#if DUAL_MIXING_EXTRUDER || ENABLED(GRADIENT_MIX) +#if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) mixer_perc_t Mixer::mix[MIXING_STEPPERS]; #endif @@ -90,9 +90,7 @@ void Mixer::normalize(const uint8_t tool_index) { SERIAL_ECHOLNPGM("]"); #endif - #if ENABLED(GRADIENT_MIX) - refresh_gradient(); - #endif + TERN_(GRADIENT_MIX, refresh_gradient()); } void Mixer::reset_vtools() { @@ -123,13 +121,11 @@ void Mixer::init() { ZERO(collector); - #if DUAL_MIXING_EXTRUDER || ENABLED(GRADIENT_MIX) + #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) update_mix_from_vtool(); #endif - #if ENABLED(GRADIENT_MIX) - update_gradient_for_planner_z(); - #endif + TERN_(GRADIENT_MIX, update_gradient_for_planner_z()); } void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*=selected_vtool*/, float (&c)[MIXING_STEPPERS]/*=collector*/) { diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index 156870b659..75028a174d 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -25,7 +25,7 @@ //#define MIXER_NORMALIZER_DEBUG -#ifndef __AVR__ // || DUAL_MIXING_EXTRUDER +#ifndef __AVR__ // || HAS_DUAL_MIXING // Use 16-bit (or fastest) data for the integer mix factors typedef uint_fast16_t mixer_comp_t; typedef uint_fast16_t mixer_accu_t; @@ -48,14 +48,14 @@ typedef int8_t mixer_perc_t; #endif enum MixTool { - FIRST_USER_VIRTUAL_TOOL = 0, - LAST_USER_VIRTUAL_TOOL = MIXING_VIRTUAL_TOOLS - 1, - NR_USER_VIRTUAL_TOOLS, - MIXER_DIRECT_SET_TOOL = NR_USER_VIRTUAL_TOOLS, + FIRST_USER_VIRTUAL_TOOL = 0 + , LAST_USER_VIRTUAL_TOOL = MIXING_VIRTUAL_TOOLS - 1 + , NR_USER_VIRTUAL_TOOLS + , MIXER_DIRECT_SET_TOOL = NR_USER_VIRTUAL_TOOLS #if HAS_MIXER_SYNC_CHANNEL - MIXER_AUTORETRACT_TOOL, + , MIXER_AUTORETRACT_TOOL #endif - NR_MIXING_VIRTUAL_TOOLS + , NR_MIXING_VIRTUAL_TOOLS }; #define MAX_VTOOLS TERN(HAS_MIXER_SYNC_CHANNEL, 254, 255) @@ -75,9 +75,7 @@ static_assert(NR_MIXING_VIRTUAL_TOOLS <= MAX_VTOOLS, "MIXING_VIRTUAL_TOOLS must int8_t start_vtool, end_vtool; // Start and end virtual tools mixer_perc_t start_mix[MIXING_STEPPERS], // Start and end mixes from those tools end_mix[MIXING_STEPPERS]; - #if ENABLED(GRADIENT_VTOOL) - int8_t vtool_index; // Use this virtual tool number as index - #endif + TERN_(GRADIENT_VTOOL, int8_t vtool_index); // Use this virtual tool number as index } gradient_t; #endif @@ -106,12 +104,8 @@ class Mixer { FORCE_INLINE static void T(const uint_fast8_t c) { selected_vtool = c; - #if ENABLED(GRADIENT_VTOOL) - refresh_gradient(); - #endif - #if DUAL_MIXING_EXTRUDER - update_mix_from_vtool(); - #endif + TERN_(GRADIENT_VTOOL, refresh_gradient()); + TERN_(HAS_DUAL_MIXING, update_mix_from_vtool()); } // Used when dealing with blocks @@ -129,7 +123,7 @@ class Mixer { MIXER_STEPPER_LOOP(i) s_color[i] = b_color[i]; } - #if DUAL_MIXING_EXTRUDER || ENABLED(GRADIENT_MIX) + #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) static mixer_perc_t mix[MIXING_STEPPERS]; // Scratch array for the Mix in proportion to 100 @@ -167,21 +161,19 @@ class Mixer { #endif } - #endif // DUAL_MIXING_EXTRUDER || GRADIENT_MIX + #endif // HAS_DUAL_MIXING || GRADIENT_MIX - #if DUAL_MIXING_EXTRUDER + #if HAS_DUAL_MIXING // Update the virtual tool from an edited mix static inline void update_vtool_from_mix() { copy_mix_to_color(color[selected_vtool]); - #if ENABLED(GRADIENT_MIX) - refresh_gradient(); - #endif + TERN_(GRADIENT_MIX, refresh_gradient()); // MIXER_STEPPER_LOOP(i) collector[i] = mix[i]; // normalize(); } - #endif // DUAL_MIXING_EXTRUDER + #endif // HAS_DUAL_MIXING #if ENABLED(GRADIENT_MIX) diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 27b7f99205..b26cff53b3 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -707,12 +707,8 @@ void MMU2::filament_runout() { if (recover) { LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); BUZZ(200, 404); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); wait_for_user_response(); BUZZ(200, 404); BUZZ(200, 404); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 3b4ac9c27a..3eb786752c 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -86,9 +86,7 @@ fil_change_settings_t fc_settings[EXTRUDERS]; #if HAS_BUZZER static void filament_change_beep(const int8_t max_beep_count, const bool init=false) { - #if HAS_LCD_MENU - if (pause_mode == PAUSE_MODE_PAUSE_PRINT) return; - #endif + if (TERN0(HAS_LCD_MENU, pause_mode == PAUSE_MODE_PAUSE_PRINT)) return; static millis_t next_buzz = 0; static int8_t runout_beep = 0; @@ -184,13 +182,9 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l host_action_prompt_button(CONTINUE_STR); host_action_prompt_show(); #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Load Filament")); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); while (wait_for_user) { - #if HAS_BUZZER - filament_change_beep(max_beep_count); - #endif + TERN_(HAS_BUZZER, filament_change_beep(max_beep_count)); idle_no_sleep(); } } @@ -235,12 +229,8 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE); #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging...")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."))); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); @@ -259,9 +249,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); } - #if ENABLED(HOST_PROMPT_SUPPORT) - filament_load_host_prompt(); // Initiate another host prompt. (NOTE: host_response_handler may also do this!) - #endif + TERN_(HOST_PROMPT_SUPPORT, filament_load_host_prompt()); // Initiate another host prompt. (NOTE: host_response_handler may also do this!) #if HAS_LCD_MENU if (show_lcd) { @@ -274,11 +262,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif // Keep looping if "Purge More" was selected - } while (false - #if HAS_LCD_MENU - || (show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE) - #endif - ); + } while (TERN0(HAS_LCD_MENU, show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)); #endif @@ -384,9 +368,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float #endif #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_open(PROMPT_INFO, PSTR("Pause"), DISMISS_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Pause"), DISMISS_STR)); if (!DEBUGGING(DRYRUN) && unload_length && thermalManager.targetTooColdToExtrude(active_extruder)) { SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); @@ -465,9 +447,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float */ void show_continue_prompt(const bool is_reload) { - #if HAS_LCD_MENU - lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING)); SERIAL_ECHO_START(); serialprintPGM(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); } @@ -497,17 +477,11 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_NOZZLE_PARKED), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED)); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_NOZZLE_PARKED), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED))); wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { - #if HAS_BUZZER - filament_change_beep(max_beep_count); - #endif + TERN_(HAS_BUZZER, filament_change_beep(max_beep_count)); // If the nozzle has timed out... if (!nozzle_timed_out) @@ -516,27 +490,18 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for the user to press the button to re-heat the nozzle, then // re-heat the nozzle, re-show the continue prompt, restart idle timers, start over if (nozzle_timed_out) { - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_HEAT); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_HEAT)); SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT)); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT))); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT)); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT))); wait_for_user_response(0, true); // Wait for LCD click or M108 - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING)); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING)); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING))); + + TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING))); // Re-enable the heaters if they timed out HOTEND_LOOP() thermalManager.reset_hotend_idle_timer(e); @@ -551,18 +516,12 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished.")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished."))); wait_for_user = true; nozzle_timed_out = false; - #if HAS_BUZZER - filament_change_beep(max_beep_count, true); - #endif + TERN_(HAS_BUZZER, filament_change_beep(max_beep_count, true)); } idle_no_sleep(); } @@ -613,9 +572,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le if (nozzle_timed_out || thermalManager.hotEnoughToExtrude(active_extruder)) // Load the new filament load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_RESUME); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_RESUME)); // Intelligent resuming #if ENABLED(FWRETRACT) @@ -641,9 +598,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le // Set extruder to saved position planner.set_e_position_mm((destination.e = current_position.e = resume_position.e)); - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_STATUS); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); #ifdef ACTION_ON_RESUMED host_action_resumed(); @@ -653,9 +608,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le --did_pause_print; - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR)); #if ENABLED(SDSUPPORT) if (did_pause_print) { @@ -668,19 +621,13 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le thermalManager.set_fans_paused(false); #endif - #if HAS_FILAMENT_SENSOR - runout.reset(); - #endif + TERN_(HAS_FILAMENT_SENSOR, runout.reset()); // Resume the print job timer if it was running if (print_job_timer.isPaused()) print_job_timer.start(); - #if HAS_DISPLAY - ui.reset_status(); - #if HAS_LCD_MENU - ui.return_to_status(); - #endif - #endif + TERN_(HAS_DISPLAY, ui.reset_status()); + TERN_(HAS_LCD_MENU, ui.return_to_status()); } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 746ce6aa3d..add3e1d8aa 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -50,15 +50,12 @@ bool Power::is_power_needed() { if (controllerFan.state()) return true; #endif - #if ENABLED(AUTO_POWER_CHAMBER_FAN) - if (thermalManager.chamberfan_speed) return true; - #endif + if (TERN0(AUTO_POWER_CHAMBER_FAN, thermalManager.chamberfan_speed)) + return true; // If any of the drivers or the bed are enabled... if (X_ENABLE_READ() == X_ENABLE_ON || Y_ENABLE_READ() == Y_ENABLE_ON || Z_ENABLE_READ() == Z_ENABLE_ON - #if HAS_HEATED_BED - || thermalManager.temp_bed.soft_pwm_amount > 0 - #endif + || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0) #if HAS_X2_ENABLE || X2_ENABLE_READ() == X_ENABLE_ON #endif @@ -75,10 +72,7 @@ bool Power::is_power_needed() { ) return true; HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0) return true; - - #if HAS_HEATED_BED - if (thermalManager.degTargetBed() > 0) return true; - #endif + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) return true; #if HOTENDS && AUTO_POWER_E_TEMP HOTEND_LOOP() if (thermalManager.degHotend(e) >= AUTO_POWER_E_TEMP) return true; diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 397b88d362..ccb85049d8 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -172,12 +172,8 @@ void PrintJobRecovery::save(const bool force/*=false*/) { // Machine state info.current_position = current_position; - #if HAS_HOME_OFFSET - info.home_offset = home_offset; - #endif - #if HAS_POSITION_SHIFT - info.position_shift = position_shift; - #endif + TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset); + TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); info.feedrate = uint16_t(feedrate_mm_s * 60.0f); #if EXTRUDERS > 1 @@ -197,9 +193,7 @@ void PrintJobRecovery::save(const bool force/*=false*/) { HOTEND_LOOP() info.target_temperature[e] = thermalManager.temp_hotend[e].target; #endif - #if HAS_HEATED_BED - info.target_temperature_bed = thermalManager.temp_bed.target; - #endif + TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.temp_bed.target); #if FAN_COUNT COPY(info.fan_speed, thermalManager.fan_speed); @@ -207,18 +201,10 @@ void PrintJobRecovery::save(const bool force/*=false*/) { #if HAS_LEVELING info.leveling = planner.leveling_active; - info.fade = ( - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - planner.z_fade_height - #else - 0 - #endif - ); + info.fade = TERN0(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height); #endif - #if ENABLED(GRADIENT_MIX) - memcpy(&info.gradient, &mixer.gradient, sizeof(info.gradient)); - #endif + TERN_(GRADIENT_MIX, memcpy(&info.gradient, &mixer.gradient, sizeof(info.gradient))); #if ENABLED(FWRETRACT) COPY(info.retract, fwretract.current_retract); @@ -244,9 +230,7 @@ void PrintJobRecovery::save(const bool force/*=false*/) { lock = true; #endif if (IS_SD_PRINTING()) save(true); - #if ENABLED(BACKUP_POWER_SUPPLY) - raise_z(); - #endif + TERN_(BACKUP_POWER_SUPPLY, raise_z()); kill(GET_TEXT(MSG_OUTAGE_RECOVERY)); } @@ -299,9 +283,7 @@ void PrintJobRecovery::resume() { // If Z homing goes to max, just reset E and home all "\n" "G28R0" - #if ENABLED(MARLIN_DEV_MODE) - "S" - #endif + TERN_(MARLIN_DEV_MODE, "S") #else // "G92.9 E0 ..." @@ -460,12 +442,8 @@ void PrintJobRecovery::resume() { // Relative axis modes gcode.axis_relative = info.axis_relative; - #if HAS_HOME_OFFSET - home_offset = info.home_offset; - #endif - #if HAS_POSITION_SHIFT - position_shift = info.position_shift; - #endif + TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset); + TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift); #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT LOOP_XYZ(i) update_workspace_offset((AxisEnum)i); #endif diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index dff21b92ad..4ce7066c15 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -82,9 +82,7 @@ class ProbeTempComp { static inline void clear_all_offsets() { clear_offsets(TSI_BED); clear_offsets(TSI_PROBE); - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - clear_offsets(TSI_EXT); - #endif + TERN_(USE_TEMP_EXT_COMPENSATION, clear_offsets(TSI_EXT)); } static bool set_offset(const TempSensorID tsi, const uint8_t idx, const int16_t offset); static void print_offsets(); diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index bd4a653e99..f74e0c741b 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -74,13 +74,9 @@ void FilamentSensorBase::filament_present(const uint8_t extruder) { void event_filament_runout() { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - if (did_pause_print) return; // Action already in progress. Purge triggered repeated runout. - #endif + if (TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) return; // Action already in progress. Purge triggered repeated runout. - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onFilamentRunout(ExtUI::getActiveTool()); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getActiveTool())); #if EITHER(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS) const char tool = '0' diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 63c9891109..83b6dd05f7 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -54,9 +54,7 @@ void SpindleLaser::init() { #endif #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); - #if ENABLED(MARLIN_DEV_MODE) - frequency = SPINDLE_LASER_FREQUENCY; - #endif + TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif } @@ -99,9 +97,7 @@ void SpindleLaser::apply_power(const cutter_power_t inpow) { // void SpindleLaser::set_direction(const bool reverse) { const bool dir_state = (reverse == SPINDLE_INVERT_DIR); // Forward (M3) HIGH when not inverted - #if ENABLED(SPINDLE_STOP_ON_DIR_CHANGE) - if (enabled() && READ(SPINDLE_DIR_PIN) != dir_state) disable(); - #endif + if (TERN0(SPINDLE_STOP_ON_DIR_CHANGE, enabled()) && READ(SPINDLE_DIR_PIN) != dir_state) disable(); WRITE(SPINDLE_DIR_PIN, dir_state); } diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 3d7ab6c360..0c2e569aa6 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -162,9 +162,7 @@ public: #endif static inline void kill() { - #if ENABLED(LASER_POWER_INLINE) - inline_disable(); - #endif + TERN_(LASER_POWER_INLINE, inline_disable()); disable(); } }; diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index bfc2e1a555..fe8fe06d6f 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -63,9 +63,9 @@ , is_stall:1 , is_stealth:1 , is_standstill:1 - #if HAS_STALLGUARD - , sg_result_reasonable:1 - #endif + #if HAS_STALLGUARD + , sg_result_reasonable:1 + #endif #endif ; #if ENABLED(TMC_DEBUG) @@ -169,9 +169,7 @@ data.is_stealth = TEST(ds, STEALTH_bp); data.is_standstill = TEST(ds, STST_bp); #endif - #if HAS_STALLGUARD - data.sg_result_reasonable = false; - #endif + TERN_(HAS_STALLGUARD, data.sg_result_reasonable = false); #endif return data; } @@ -213,9 +211,7 @@ SERIAL_PRINTLN(data.drv_status, HEX); if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); - #if ENABLED(TMC_DEBUG) - tmc_report_all(true, true, true, true); - #endif + TERN_(TMC_DEBUG, tmc_report_all(true, true, true, true)); kill(PSTR("Driver error")); } #endif @@ -446,9 +442,7 @@ (void)monitor_tmc_driver(stepperE7, need_update_error_counters, need_debug_reporting); #endif - #if ENABLED(TMC_DEBUG) - if (need_debug_reporting) SERIAL_EOL(); - #endif + if (TERN0(TMC_DEBUG, need_debug_reporting)) SERIAL_EOL(); } } diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 6838aa433c..d7b6a944df 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -69,15 +69,9 @@ class TMCStorage { } struct { - #if HAS_STEALTHCHOP - bool stealthChop_enabled = false; - #endif - #if ENABLED(HYBRID_THRESHOLD) - uint8_t hybrid_thrs = 0; - #endif - #if USE_SENSORLESS - int16_t homing_thrs = 0; - #endif + TERN_(HAS_STEALTHCHOP, bool stealthChop_enabled = false); + TERN_(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0); + TERN_(USE_SENSORLESS, int16_t homing_thrs = 0); } stored; }; @@ -118,9 +112,7 @@ class TMCMarlin : public TMC, public TMCStorage { } void set_pwm_thrs(const uint32_t thrs) { TMC::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); - #if HAS_LCD_MENU - this->stored.hybrid_thrs = thrs; - #endif + TERN_(HAS_LCD_MENU, this->stored.hybrid_thrs = thrs); } #endif @@ -129,9 +121,7 @@ class TMCMarlin : public TMC, public TMCStorage { void homing_threshold(int16_t sgt_val) { sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); TMC::sgt(sgt_val); - #if HAS_LCD_MENU - this->stored.homing_thrs = sgt_val; - #endif + TERN_(HAS_LCD_MENU, this->stored.homing_thrs = sgt_val); } #if ENABLED(SPI_ENDSTOPS) bool test_stall_status(); @@ -184,9 +174,7 @@ class TMCMarlin : public TMC220 } void set_pwm_thrs(const uint32_t thrs) { TMC2208Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); - #if HAS_LCD_MENU - this->stored.hybrid_thrs = thrs; - #endif + TERN_(HAS_LCD_MENU, this->stored.hybrid_thrs = thrs); } #endif @@ -231,9 +219,7 @@ class TMCMarlin : public TMC220 } void set_pwm_thrs(const uint32_t thrs) { TMC2209Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); - #if HAS_LCD_MENU - this->stored.hybrid_thrs = thrs; - #endif + TERN_(HAS_LCD_MENU, this->stored.hybrid_thrs = thrs); } #endif #if USE_SENSORLESS @@ -241,9 +227,7 @@ class TMCMarlin : public TMC220 void homing_threshold(int16_t sgt_val) { sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); TMC2209Stepper::SGTHRS(sgt_val); - #if HAS_LCD_MENU - this->stored.homing_thrs = sgt_val; - #endif + TERN_(HAS_LCD_MENU, this->stored.homing_thrs = sgt_val); } #endif @@ -283,9 +267,7 @@ class TMCMarlin : public TMC266 void homing_threshold(int16_t sgt_val) { sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); TMC2660Stepper::sgt(sgt_val); - #if HAS_LCD_MENU - this->stored.homing_thrs = sgt_val; - #endif + TERN_(HAS_LCD_MENU, this->stored.homing_thrs = sgt_val); } #endif @@ -367,9 +349,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z struct slow_homing_t { xy_ulong_t acceleration; - #if HAS_CLASSIC_JERK - xy_float_t jerk_xy; - #endif + TERN_(HAS_CLASSIC_JERK, xy_float_t jerk_xy); }; #endif diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 0867e1e010..9f3833803a 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -165,9 +165,7 @@ int8_t g26_prime_flag; bool user_canceled() { if (!ui.button_pressed()) return false; // Return if the button isn't pressed ui.set_status_P(GET_TEXT(MSG_G26_CANCELED), 99); - #if HAS_LCD_MENU - ui.quick_feedback(); - #endif + TERN_(HAS_LCD_MENU, ui.quick_feedback()); ui.wait_for_release(); return true; } @@ -301,9 +299,7 @@ inline bool look_for_lines_to_connect() { GRID_LOOP(i, j) { - #if HAS_LCD_MENU - if (user_canceled()) return true; - #endif + if (TERN0(HAS_LCD_MENU, user_canceled())) return true; if (i < (GRID_MAX_POINTS_X)) { // Can't connect to anything farther to the right than GRID_MAX_POINTS_X. // Already a half circle at the edge of the bed. @@ -364,9 +360,7 @@ inline bool turn_on_heaters() { #if HAS_SPI_LCD ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99); ui.quick_feedback(); - #if HAS_LCD_MENU - ui.capture(); - #endif + TERN_(HAS_LCD_MENU, ui.capture()); #endif thermalManager.setTargetBed(g26_bed_temp); @@ -390,11 +384,10 @@ inline bool turn_on_heaters() { // Wait for the temperature to stabilize if (!thermalManager.wait_for_hotend(active_extruder, true - #if G26_CLICK_CAN_CANCEL - , true - #endif - ) - ) return G26_ERR; + #if G26_CLICK_CAN_CANCEL + , true + #endif + )) return G26_ERR; #if HAS_SPI_LCD ui.reset_status(); @@ -665,9 +658,7 @@ void GcodeSuite::G26() { move_to(destination, 0.0); move_to(destination, g26_ooze_amount); - #if HAS_LCD_MENU - ui.capture(); - #endif + TERN_(HAS_LCD_MENU, ui.capture()); #if DISABLED(ARC_SUPPORT) @@ -762,9 +753,7 @@ void GcodeSuite::G26() { feedrate_mm_s = old_feedrate; destination = current_position; - #if HAS_LCD_MENU - if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation - #endif + if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation #else // !ARC_SUPPORT @@ -788,9 +777,7 @@ void GcodeSuite::G26() { for (int8_t ind = start_ind; ind <= end_ind; ind++) { - #if HAS_LCD_MENU - if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation - #endif + if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation xyz_float_t p = { circle.x + _COS(ind ), circle.y + _SIN(ind ), g26_layer_height }, q = { circle.x + _COS(ind + 1), circle.y + _SIN(ind + 1), g26_layer_height }; @@ -833,14 +820,10 @@ void GcodeSuite::G26() { planner.calculate_volumetric_multipliers(); #endif - #if HAS_LCD_MENU - ui.release(); // Give back control of the LCD - #endif + TERN_(HAS_LCD_MENU, ui.release()); // Give back control of the LCD if (!g26_keep_heaters_on) { - #if HAS_HEATED_BED - thermalManager.setTargetBed(0); - #endif + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(0)); thermalManager.setTargetHotend(active_extruder, 0); } } diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index ad2e01f093..3effc3173b 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -73,9 +73,7 @@ void GcodeSuite::M420() { #endif GRID_LOOP(x, y) { Z_VALUES(x, y) = 0.001 * random(-200, 200); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y))); } SERIAL_ECHOPGM("Simulated " STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh "); SERIAL_ECHOPAIR(" (", x_min); @@ -178,13 +176,9 @@ void GcodeSuite::M420() { // Subtract the mean from all values GRID_LOOP(x, y) { Z_VALUES(x, y) -= zmean; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y))); } - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); } #endif @@ -206,9 +200,7 @@ void GcodeSuite::M420() { if (leveling_is_valid()) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) print_bilinear_leveling_grid(); - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - print_bilinear_leveling_grid_virt(); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, print_bilinear_leveling_grid_virt()); #elif ENABLED(MESH_BED_LEVELING) SERIAL_ECHOLNPGM("Mesh Bed Level data:"); mbl.report_mesh(); diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index f316b4a7a1..165ae88709 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -283,9 +283,7 @@ G29_TYPE GcodeSuite::G29() { */ if (!g29_in_progress) { - #if HAS_MULTI_HOTEND - if (active_extruder != 0) tool_change(0); - #endif + TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) abl_probe_index = -1; @@ -322,12 +320,8 @@ G29_TYPE GcodeSuite::G29() { if (WITHIN(i, 0, GRID_MAX_POINTS_X - 1) && WITHIN(j, 0, GRID_MAX_POINTS_Y)) { set_bed_leveling_enabled(false); z_values[i][j] = rz; - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(i, j, rz); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, rz)); set_bed_leveling_enabled(abl_should_enable); if (abl_should_enable) report_current_position(); } @@ -492,14 +486,10 @@ G29_TYPE GcodeSuite::G29() { // Abort current G29 procedure, go back to idle state if (seenA && g29_in_progress) { SERIAL_ECHOLNPGM("Manual G29 aborted"); - #if HAS_SOFTWARE_ENDSTOPS - soft_endstops_enabled = saved_soft_endstops_state; - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state); set_bed_leveling_enabled(abl_should_enable); g29_in_progress = false; - #if ENABLED(LCD_BED_LEVELING) - ui.wait_for_move = false; - #endif + TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); } // Query G29 status @@ -517,9 +507,7 @@ G29_TYPE GcodeSuite::G29() { if (abl_probe_index == 0) { // For the initial G29 S2 save software endstop state - #if HAS_SOFTWARE_ENDSTOPS - saved_soft_endstops_state = soft_endstops_enabled; - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, saved_soft_endstops_state = soft_endstops_enabled); // Move close to the bed before the first point do_blocking_move_to_z(0); } @@ -551,9 +539,7 @@ G29_TYPE GcodeSuite::G29() { const float newz = measured_z + zoffset; z_values[meshCount.x][meshCount.y] = newz; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(meshCount, newz); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, newz)); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_P(PSTR("Save X"), meshCount.x, SP_Y_STR, meshCount.y, SP_Z_STR, measured_z + zoffset); @@ -580,9 +566,7 @@ G29_TYPE GcodeSuite::G29() { probePos = probe_position_lf + gridSpacing * meshCount.asFloat(); - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - indexIntoAB[meshCount.x][meshCount.y] = abl_probe_index; - #endif + TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = abl_probe_index); // Keep looping till a reachable point is found if (position_is_reachable(probePos)) break; @@ -606,9 +590,7 @@ G29_TYPE GcodeSuite::G29() { SERIAL_ECHOLNPGM("Grid probing done."); // Re-enable software endstops, if needed - #if HAS_SOFTWARE_ENDSTOPS - soft_endstops_enabled = saved_soft_endstops_state; - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state); } #elif ENABLED(AUTO_BED_LEVELING_3POINT) @@ -629,9 +611,7 @@ G29_TYPE GcodeSuite::G29() { SERIAL_ECHOLNPGM("3-point probing done."); // Re-enable software endstops, if needed - #if HAS_SOFTWARE_ENDSTOPS - soft_endstops_enabled = saved_soft_endstops_state; - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state); if (!dryrun) { vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal(); @@ -688,9 +668,7 @@ G29_TYPE GcodeSuite::G29() { probePos = probe_position_lf + gridSpacing * meshCount.asFloat(); - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index; // 0... - #endif + TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index); // 0... #if IS_KINEMATIC // Avoid probing outside the round or hexagonal area @@ -698,9 +676,7 @@ G29_TYPE GcodeSuite::G29() { #endif if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", int(GRID_MAX_POINTS), "."); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(GRID_MAX_POINTS)); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(GRID_MAX_POINTS))); measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(probePos, raise_after, verbose_level); @@ -712,9 +688,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(PROBE_TEMP_COMPENSATION) temp_comp.compensate_measurement(TSI_BED, thermalManager.degBed(), measured_z); temp_comp.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), measured_z); - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), measured_z); - #endif + TERN_(USE_TEMP_EXT_COMPENSATION, temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), measured_z)); #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -730,9 +704,7 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) z_values[meshCount.x][meshCount.y] = measured_z + zoffset; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(meshCount, z_values[meshCount.x][meshCount.y]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, z_values[meshCount.x][meshCount.y])); #endif @@ -748,9 +720,7 @@ G29_TYPE GcodeSuite::G29() { LOOP_L_N(i, 3) { if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", int(i), "/3."); - #if HAS_DISPLAY - ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i)); - #endif + TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i))); // Retain the last probe position probePos = points[i]; @@ -773,9 +743,7 @@ G29_TYPE GcodeSuite::G29() { #endif // AUTO_BED_LEVELING_3POINT - #if HAS_DISPLAY - ui.reset_status(); - #endif + TERN_(HAS_DISPLAY, ui.reset_status()); // Stow the probe. No raise for FIX_MOUNTED_PROBE. if (probe.stow()) { @@ -799,9 +767,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(PROBE_MANUALLY) g29_in_progress = false; - #if ENABLED(LCD_BED_LEVELING) - ui.wait_for_move = false; - #endif + TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); #endif // Calculate leveling, print reports, correct the position @@ -813,9 +779,7 @@ G29_TYPE GcodeSuite::G29() { refresh_bed_level(); - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - print_bilinear_leveling_grid_virt(); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, print_bilinear_leveling_grid_virt()); #elif ENABLED(AUTO_BED_LEVELING_LINEAR) diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 3cd2673d66..74514bf417 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -55,12 +55,8 @@ void GcodeSuite::M421() { SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else { z_values[ix][iy] = parser.value_linear_units() + (hasQ ? z_values[ix][iy] : 0); - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); } } diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 6c8fafe23f..7c363312ec 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -62,9 +62,7 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" void GcodeSuite::G29() { static int mbl_probe_index = -1; - #if HAS_SOFTWARE_ENDSTOPS - static bool saved_soft_endstops_state; - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, static bool saved_soft_endstops_state); MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport); if (!WITHIN(state, 0, 5)) { @@ -111,9 +109,7 @@ void GcodeSuite::G29() { else { // Save Z for the previous mesh position mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); - #if HAS_SOFTWARE_ENDSTOPS - soft_endstops_enabled = saved_soft_endstops_state; - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state); } // If there's another point to sample, move there with optional lift. if (mbl_probe_index < GRID_MAX_POINTS) { @@ -147,9 +143,7 @@ void GcodeSuite::G29() { planner.synchronize(); #endif - #if ENABLED(LCD_BED_LEVELING) - ui.wait_for_move = false; - #endif + TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); } break; @@ -178,9 +172,7 @@ void GcodeSuite::G29() { if (parser.seenval('Z')) { mbl.z_values[ix][iy] = parser.value_linear_units(); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy]); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy])); } else return echo_not_entered('Z'); diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index bd65c21ad3..6a0ac50af6 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -63,9 +63,7 @@ void GcodeSuite::M421() { else { float &zval = ubl.z_values[ij.x][ij.y]; zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(ij.x, ij.y, zval); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 8c699b5fd3..e44d94fc55 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -126,22 +126,16 @@ */ destination.set(safe_homing_xy, current_position.z); - #if HOMING_Z_WITH_PROBE - destination -= probe.offset_xy; - #endif + TERN_(HOMING_Z_WITH_PROBE, destination -= probe.offset_xy); if (position_is_reachable(destination)) { if (DEBUGGING(LEVELING)) DEBUG_POS("home_z_safely", destination); // This causes the carriage on Dual X to unpark - #if ENABLED(DUAL_X_CARRIAGE) - active_extruder_parked = false; - #endif + TERN_(DUAL_X_CARRIAGE, active_extruder_parked = false); - #if ENABLED(SENSORLESS_HOMING) - safe_delay(500); // Short delay needed to settle - #endif + TERN_(SENSORLESS_HOMING, safe_delay(500)); // Short delay needed to settle do_blocking_move_to_xy(destination); homeaxis(Z_AXIS); @@ -175,9 +169,7 @@ void end_slow_homing(const slow_homing_t &slow_homing) { planner.settings.max_acceleration_mm_per_s2[X_AXIS] = slow_homing.acceleration.x; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = slow_homing.acceleration.y; - #if HAS_CLASSIC_JERK - planner.max_jerk = slow_homing.jerk_xy; - #endif + TERN_(HAS_CLASSIC_JERK, planner.max_jerk = slow_homing.jerk_xy); planner.reset_acceleration_rates(); } @@ -237,22 +229,18 @@ void GcodeSuite::G28() { #if HAS_LEVELING // Cancel the active G29 session - #if ENABLED(PROBE_MANUALLY) - g29_in_progress = false; - #endif + TERN_(PROBE_MANUALLY, g29_in_progress = false); - #if ENABLED(RESTORE_LEVELING_AFTER_G28) - const bool leveling_was_active = planner.leveling_active; - #endif + TERN_(RESTORE_LEVELING_AFTER_G28, const bool leveling_was_active = planner.leveling_active); set_bed_leveling_enabled(false); #endif - #if ENABLED(CNC_WORKSPACE_PLANES) - workspace_plane = PLANE_XY; - #endif + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) - #define HAS_HOMING_CURRENT (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2)) + #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) + #define HAS_HOMING_CURRENT 1 + #endif #if HAS_HOMING_CURRENT auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){ @@ -280,9 +268,7 @@ void GcodeSuite::G28() { #endif #endif - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - slow_homing_t slow_homing = begin_slow_homing(); - #endif + TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing_t slow_homing = begin_slow_homing()); // Always home with tool 0 active #if HAS_MULTI_HOTEND @@ -292,9 +278,7 @@ void GcodeSuite::G28() { tool_change(0, true); #endif - #if HAS_DUPLICATION_MODE - extruder_duplication_enabled = false; - #endif + TERN_(HAS_DUPLICATION_MODE, extruder_duplication_enabled = false); remember_feedrate_scaling_off(); @@ -306,9 +290,7 @@ void GcodeSuite::G28() { home_delta(); - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - end_slow_homing(slow_homing); - #endif + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); #else // NOT DELTA @@ -380,17 +362,13 @@ void GcodeSuite::G28() { if (DISABLED(HOME_Y_BEFORE_X) && doY) homeaxis(Y_AXIS); - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - end_slow_homing(slow_homing); - #endif + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); // Home Z last if homing towards the bed #if Z_HOME_DIR < 0 if (doZ) { - #if ENABLED(BLTOUCH) - bltouch.init(); - #endif + TERN_(BLTOUCH, bltouch.init()); #if ENABLED(Z_SAFE_HOMING) home_z_safely(); #else @@ -425,9 +403,7 @@ void GcodeSuite::G28() { if (dxc_is_duplicating()) { - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - slow_homing = begin_slow_homing(); - #endif + TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing = begin_slow_homing()); // Always home the 2nd (right) extruder first active_extruder = 1; @@ -448,9 +424,7 @@ void GcodeSuite::G28() { dual_x_carriage_mode = IDEX_saved_mode; stepper.set_directions(); - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - end_slow_homing(slow_homing); - #endif + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); } #endif // DUAL_X_CARRIAGE @@ -458,18 +432,14 @@ void GcodeSuite::G28() { endstops.not_homing(); // Clear endstop state for polled stallGuard endstops - #if ENABLED(SPI_ENDSTOPS) - endstops.clear_endstop_state(); - #endif + TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state()); #if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE) // move to a height where we can use the full xy-area do_blocking_move_to_z(delta_clip_start_height); #endif - #if ENABLED(RESTORE_LEVELING_AFTER_G28) - set_bed_leveling_enabled(leveling_was_active); - #endif + TERN_(RESTORE_LEVELING_AFTER_G28, set_bed_leveling_enabled(leveling_was_active)); restore_feedrate_and_scaling(); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 6f0f8a5562..d7112de506 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -63,12 +63,7 @@ enum CalEnum : char { // the 7 main calibration points - #define LOOP_CAL_RAD(VAR) LOOP_CAL_PT(VAR, __A, _7P_STEP) #define LOOP_CAL_ACT(VAR, _4P, _OP) LOOP_CAL_PT(VAR, _OP ? _AB : __A, _4P ? _4P_STEP : _7P_STEP) -#if HOTENDS > 1 - const uint8_t old_tool_index = active_extruder; - #define AC_CLEANUP() ac_cleanup(old_tool_index) -#else - #define AC_CLEANUP() ac_cleanup() -#endif +TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index = active_extruder); float lcd_probe_pt(const xy_pos_t &xy); @@ -79,9 +74,7 @@ void ac_home() { } void ac_setup(const bool reset_bed) { - #if HOTENDS > 1 - tool_change(0, true); - #endif + TERN_(HAS_MULTI_HOTEND, tool_change(0, true)); planner.synchronize(); remember_feedrate_scaling_off(); @@ -91,21 +84,11 @@ void ac_setup(const bool reset_bed) { #endif } -void ac_cleanup( - #if HOTENDS > 1 - const uint8_t old_tool_index - #endif -) { - #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) - do_blocking_move_to_z(delta_clip_start_height); - #endif - #if HAS_BED_PROBE - probe.stow(); - #endif +void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) { + TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); + TERN_(HAS_BED_PROBE, probe.stow()); restore_feedrate_and_scaling(); - #if HOTENDS > 1 - tool_change(old_tool_index, true); - #endif + TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, true)); } void print_signed_float(PGM_P const prefix, const float &f) { @@ -488,7 +471,7 @@ void GcodeSuite::G33() { zero_std_dev_old = zero_std_dev; if (!probe_calibration_points(z_at_pt, probe_points, towers_set, stow_after_each)) { SERIAL_ECHOLNPGM("Correct delta settings with M665 and M666"); - return AC_CLEANUP(); + return ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); } zero_std_dev = std_dev_points(z_at_pt, _0p_calibration, _1p_calibration, _4p_calibration, _4p_opposite_points); @@ -659,7 +642,7 @@ void GcodeSuite::G33() { } while (((zero_std_dev < test_precision && iterations < 31) || iterations <= force_iterations) && zero_std_dev > calibration_precision); - AC_CLEANUP(); + ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); } #endif // DELTA_AUTO_CALIBRATION diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 091619c6ff..8c321df58c 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -113,15 +113,11 @@ void GcodeSuite::G34() { // Disable the leveling matrix before auto-aligning #if HAS_LEVELING - #if ENABLED(RESTORE_LEVELING_AFTER_G34) - const bool leveling_was_active = planner.leveling_active; - #endif + TERN_(RESTORE_LEVELING_AFTER_G34, const bool leveling_was_active = planner.leveling_active); set_bed_leveling_enabled(false); #endif - #if ENABLED(CNC_WORKSPACE_PLANES) - workspace_plane = PLANE_XY; - #endif + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); // Always home with tool 0 active #if HAS_MULTI_HOTEND @@ -129,18 +125,12 @@ void GcodeSuite::G34() { tool_change(0, true); #endif - #if HAS_DUPLICATION_MODE - extruder_duplication_enabled = false; - #endif + TERN_(HAS_DUPLICATION_MODE, extruder_duplication_enabled = false); - #if BOTH(BLTOUCH, BLTOUCH_HS_MODE) - // In BLTOUCH HS mode, the probe travels in a deployed state. - // Users of G34 might have a badly misaligned bed, so raise Z by the - // length of the deployed pin (BLTOUCH stroke < 7mm) - #define Z_BASIC_CLEARANCE Z_CLEARANCE_BETWEEN_PROBES + 7.0f - #else - #define Z_BASIC_CLEARANCE Z_CLEARANCE_BETWEEN_PROBES - #endif + // In BLTOUCH HS mode, the probe travels in a deployed state. + // Users of G34 might have a badly misaligned bed, so raise Z by the + // length of the deployed pin (BLTOUCH stroke < 7mm) + #define Z_BASIC_CLEARANCE Z_CLEARANCE_BETWEEN_PROBES + 7.0f * BOTH(BLTOUCH, BLTOUCH_HS_MODE) // Compute a worst-case clearance height to probe from. After the first // iteration this will be re-calculated based on the actual bed position @@ -386,9 +376,7 @@ void GcodeSuite::G34() { #endif // Restore the active tool after homing - #if HAS_MULTI_HOTEND - tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous tool for parking extruder - #endif + TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER))); // Fetch previous tool for parking extruder #if HAS_LEVELING && ENABLED(RESTORE_LEVELING_AFTER_G34) set_bed_leveling_enabled(leveling_was_active); diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index b9dcc8f284..18b5dc56ab 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -285,37 +285,19 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - #if ENABLED(CALIBRATION_MEASURE_RIGHT) - probe_side(m, uncertainty, RIGHT, probe_top_at_edge); - #endif - - #if ENABLED(CALIBRATION_MEASURE_FRONT) - probe_side(m, uncertainty, FRONT, probe_top_at_edge); - #endif - - #if ENABLED(CALIBRATION_MEASURE_LEFT) - probe_side(m, uncertainty, LEFT, probe_top_at_edge); - #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - probe_side(m, uncertainty, BACK, probe_top_at_edge); - #endif + TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); // Compute the measured center of the calibration object. - #if HAS_X_CENTER - m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2; - #endif - #if HAS_Y_CENTER - m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2; - #endif + TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); + TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); // Compute the outside diameter of the nozzle at the height // at which it makes contact with the calibration object - #if HAS_X_CENTER - m.nozzle_outer_dimension.x = m.obj_side[RIGHT] - m.obj_side[LEFT] - dimensions.x; - #endif - #if HAS_Y_CENTER - m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y; - #endif + TERN_(HAS_X_CENTER, m.nozzle_outer_dimension.x = m.obj_side[RIGHT] - m.obj_side[LEFT] - dimensions.x); + TERN_(HAS_Y_CENTER, m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y); park_above_object(m, uncertainty); @@ -544,13 +526,9 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty) HOTEND_LOOP() calibrate_toolhead(m, uncertainty, e); - #if HAS_HOTEND_OFFSET - normalize_hotend_offsets(); - #endif + TERN_(HAS_HOTEND_OFFSET, normalize_hotend_offsets()); - #if HAS_MULTI_HOTEND - set_nozzle(m, 0); - #endif + TERN_(HAS_MULTI_HOTEND, set_nozzle(m, 0)); } /** @@ -567,9 +545,7 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty) inline void calibrate_all() { measurements_t m; - #if HAS_HOTEND_OFFSET - reset_hotend_offsets(); - #endif + TERN_(HAS_HOTEND_OFFSET, reset_hotend_offsets()); TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); @@ -577,9 +553,7 @@ inline void calibrate_all() { // Do a fast and rough calibration of the toolheads calibrate_all_toolheads(m, CALIBRATION_MEASUREMENT_UNKNOWN); - #if ENABLED(BACKLASH_GCODE) - calibrate_backlash(m, CALIBRATION_MEASUREMENT_UNCERTAIN); - #endif + TERN_(BACKLASH_GCODE, calibrate_backlash(m, CALIBRATION_MEASUREMENT_UNCERTAIN)); // Cycle the toolheads so the servos settle into their "natural" positions #if HAS_MULTI_HOTEND diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 50b099bd1c..02895c7e05 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -178,9 +178,7 @@ void GcodeSuite::G76() { report_temps(next_temp_report); // Disable leveling so it won't mess with us - #if HAS_LEVELING - set_bed_leveling_enabled(false); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); for (;;) { thermalManager.setTargetBed(target_bed); @@ -214,9 +212,7 @@ void GcodeSuite::G76() { // Cleanup thermalManager.setTargetBed(0); - #if HAS_LEVELING - set_bed_leveling_enabled(true); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(true)); } // do_bed_cal /******************************************** @@ -240,9 +236,7 @@ void GcodeSuite::G76() { wait_for_temps(target_bed, target_probe, next_temp_report); // Disable leveling so it won't mess with us - #if HAS_LEVELING - set_bed_leveling_enabled(false); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); bool timeout = false; for (;;) { @@ -273,9 +267,7 @@ void GcodeSuite::G76() { // Cleanup thermalManager.setTargetBed(0); - #if HAS_LEVELING - set_bed_leveling_enabled(true); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(true)); SERIAL_ECHOLNPGM("Final compensation values:"); temp_comp.print_offsets(); diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index c1e8b0e9f8..175a4d4034 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -263,9 +263,7 @@ void GcodeSuite::M48() { restore_feedrate_and_scaling(); // Re-enable bed level correction if it had been on - #if HAS_LEVELING - set_bed_leveling_enabled(was_enabled); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(was_enabled)); report_current_position(); } diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index b9192198bd..0ea4fd7c17 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -142,9 +142,7 @@ void GcodeSuite::M205() { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { planner.junction_deviation_mm = junc_dev; - #if ENABLED(LIN_ADVANCE) - planner.recalculate_max_e_jerk(); - #endif + TERN_(LIN_ADVANCE, planner.recalculate_max_e_jerk()); } else SERIAL_ERROR_MSG("?J out of range (0.01 to 0.3)"); diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index baf5efb137..ace2aabf61 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -340,12 +340,8 @@ void GcodeSuite::M43() { #if HAS_RESUME_CONTINUE KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("M43 Wait Called"), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("M43 Wait Called"), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called"))); #endif for (;;) { @@ -366,9 +362,7 @@ void GcodeSuite::M43() { } } - #if HAS_RESUME_CONTINUE - if (!wait_for_user) break; - #endif + if (TERN0(HAS_RESUME_CONTINUE, !wait_for_user)) break; safe_delay(200); } diff --git a/Marlin/src/gcode/control/M108_M112_M410.cpp b/Marlin/src/gcode/control/M108_M112_M410.cpp index cb4220507d..ea6ab20d0f 100644 --- a/Marlin/src/gcode/control/M108_M112_M410.cpp +++ b/Marlin/src/gcode/control/M108_M112_M410.cpp @@ -31,9 +31,7 @@ * M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature. */ void GcodeSuite::M108() { - #if HAS_RESUME_CONTINUE - wait_for_user = false; - #endif + TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); wait_for_heatup = false; } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index d69654a959..850e02e475 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -37,9 +37,7 @@ void GcodeSuite::M17() { if (parser.seen('X')) ENABLE_AXIS_X(); if (parser.seen('Y')) ENABLE_AXIS_Y(); if (parser.seen('Z')) ENABLE_AXIS_Z(); - #if HAS_E_STEPPER_ENABLE - if (parser.seen('E')) enable_e_steppers(); - #endif + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) enable_e_steppers(); } else { LCD_MESSAGEPGM(MSG_NO_MOVE); @@ -60,9 +58,7 @@ void GcodeSuite::M18_M84() { if (parser.seen('X')) DISABLE_AXIS_X(); if (parser.seen('Y')) DISABLE_AXIS_Y(); if (parser.seen('Z')) DISABLE_AXIS_Z(); - #if HAS_E_STEPPER_ENABLE - if (parser.seen('E')) disable_e_steppers(); - #endif + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) disable_e_steppers(); } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index a61a4a1943..8f54c5d6fb 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -86,12 +86,8 @@ void GcodeSuite::M907() { * M908: Control digital trimpot directly (M908 P S) */ void GcodeSuite::M908() { - #if HAS_DIGIPOTSS - stepper.digitalPotWrite(parser.intval('P'), parser.intval('S')); - #endif - #if ENABLED(DAC_STEPPER_CURRENT) - dac_current_raw(parser.byteval('P', -1), parser.ushortval('S', 0)); - #endif + TERN_(HAS_DIGIPOTSS, stepper.digitalPotWrite(parser.intval('P'), parser.intval('S'))); + TERN_(DAC_STEPPER_CURRENT, dac_current_raw(parser.byteval('P', -1), parser.ushortval('S', 0))); } #endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 4039e8c53d..12b0892d58 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -56,11 +56,7 @@ */ void GcodeSuite::M125() { // Initial retract before move to filament change position - const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 - #ifdef PAUSE_PARK_RETRACT_LENGTH - + (PAUSE_PARK_RETRACT_LENGTH) - #endif - ); + const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH)); xyz_pos_t park_point = NOZZLE_PARK_POINT; @@ -75,23 +71,14 @@ void GcodeSuite::M125() { park_point += hotend_offset[active_extruder]; #endif - #if ENABLED(SDSUPPORT) - const bool sd_printing = IS_SD_PRINTING(); - #else - constexpr bool sd_printing = false; - #endif + const bool sd_printing = TERN0(SDSUPPORT, IS_SD_PRINTING()); - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); - const bool show_lcd = parser.seenval('P'); - #else - constexpr bool show_lcd = false; - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); + + const bool show_lcd = TERN0(HAS_LCD_MENU, parser.seenval('P')); if (pause_print(retract, park_point, 0, show_lcd)) { - #if ENABLED(POWER_LOSS_RECOVERY) - if (recovery.enabled) recovery.save(true); - #endif + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); if (!sd_printing || show_lcd) { wait_for_confirmation(false, 0); resume_print(0, 0, -retract, 0); diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index fc7702796b..be4390aafc 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -112,11 +112,7 @@ void GcodeSuite::M600() { #endif // Initial retract before move to filament change position - const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 - #ifdef PAUSE_PARK_RETRACT_LENGTH - + (PAUSE_PARK_RETRACT_LENGTH) - #endif - ); + const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH)); xyz_pos_t park_point NOZZLE_PARK_POINT; @@ -149,11 +145,9 @@ void GcodeSuite::M600() { : fc_settings[active_extruder].load_length); #endif - const int beep_count = parser.intval('B', + const int beep_count = parser.intval('B', -1 #ifdef FILAMENT_CHANGE_ALERT_BEEPS - FILAMENT_CHANGE_ALERT_BEEPS - #else - -1 + + 1 + FILAMENT_CHANGE_ALERT_BEEPS #endif ); @@ -173,9 +167,7 @@ void GcodeSuite::M600() { tool_change(active_extruder_before_filament_change, false); #endif - #if ENABLED(MIXING_EXTRUDER) - mixer.T(old_mixing_tool); // Restore original mixing tool - #endif + TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 9f89f2dab7..45e6b394af 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -84,9 +84,7 @@ void GcodeSuite::M701() { if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); // Show initial "wait for load" message - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder)); #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) // Change toolhead if specified @@ -129,14 +127,10 @@ void GcodeSuite::M701() { tool_change(active_extruder_before_filament_change, false); #endif - #if ENABLED(MIXING_EXTRUDER) - mixer.T(old_mixing_tool); // Restore original mixing tool - #endif + TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool // Show status screen - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_STATUS); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); } /** @@ -190,9 +184,7 @@ void GcodeSuite::M702() { if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); // Show initial "wait for unload" message - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder)); #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) // Change toolhead if specified @@ -241,14 +233,10 @@ void GcodeSuite::M702() { tool_change(active_extruder_before_filament_change, false); #endif - #if ENABLED(MIXING_EXTRUDER) - mixer.T(old_mixing_tool); // Restore original mixing tool - #endif + TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool // Show status screen - #if HAS_LCD_MENU - lcd_pause_show_message(PAUSE_MESSAGE_STATUS); - #endif + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 8d8cdc7557..dbcd819d70 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -74,9 +74,7 @@ void GcodeSuite::M1000() { #else recovery.cancel(); #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPrintTimerStopped(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerStopped()); } else recovery.resume(); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index dd2ede5d22..693410861d 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -218,9 +218,7 @@ void GcodeSuite::dwell(millis_t time) { } } - #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_prompt_end(); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end()); #ifdef G29_SUCCESS_COMMANDS process_subcommands_now_P(PSTR(G29_SUCCESS_COMMANDS)); diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 9df5002e6e..98db10b08b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -396,24 +396,18 @@ private: #endif ); - #if ENABLED(ARC_SUPPORT) - static void G2_G3(const bool clockwise); - #endif + TERN_(ARC_SUPPORT, static void G2_G3(const bool clockwise)); static void G4(); - #if ENABLED(BEZIER_CURVE_SUPPORT) - static void G5(); - #endif + TERN_(BEZIER_CURVE_SUPPORT, static void G5()); #if ENABLED(FWRETRACT) static void G10(); static void G11(); #endif - #if ENABLED(NOZZLE_CLEAN_FEATURE) - static void G12(); - #endif + TERN_(NOZZLE_CLEAN_FEATURE, static void G12()); #if ENABLED(CNC_WORKSPACE_PLANES) static void G17(); @@ -426,13 +420,9 @@ private: static void G21(); #endif - #if ENABLED(G26_MESH_VALIDATION) - static void G26(); - #endif + TERN_(G26_MESH_VALIDATION, static void G26()); - #if ENABLED(NOZZLE_PARK_FEATURE) - static void G27(); - #endif + TERN_(NOZZLE_PARK_FEATURE, static void G27()); static void G28(); @@ -454,22 +444,16 @@ private: #endif #endif - #if ENABLED(DELTA_AUTO_CALIBRATION) - static void G33(); - #endif + TERN_(DELTA_AUTO_CALIBRATION, static void G33()); #if ENABLED(Z_STEPPER_AUTO_ALIGN) static void G34(); static void M422(); #endif - #if ENABLED(G38_PROBE_TARGET) - static void G38(const int8_t subcode); - #endif + TERN_(G38_PROBE_TARGET, static void G38(const int8_t subcode)); - #if HAS_MESH - static void G42(); - #endif + TERN_(HAS_MESH, static void G42()); #if ENABLED(CNC_COORDINATE_SYSTEMS) static void G53(); @@ -481,28 +465,20 @@ private: static void G59(); #endif - #if ENABLED(PROBE_TEMP_COMPENSATION) - static void G76(); - #endif + TERN_(PROBE_TEMP_COMPENSATION, static void G76()); #if SAVED_POSITIONS static void G60(); static void G61(); #endif - #if ENABLED(GCODE_MOTION_MODES) - static void G80(); - #endif + TERN_(GCODE_MOTION_MODES, static void G80()); static void G92(); - #if ENABLED(CALIBRATION_GCODE) - static void G425(); - #endif + TERN_(CALIBRATION_GCODE, static void G425()); - #if HAS_RESUME_CONTINUE - static void M0_M1(); - #endif + TERN_(HAS_RESUME_CONTINUE, static void M0_M1()); #if HAS_CUTTER static void M3_M4(const bool is_M4); @@ -510,22 +486,14 @@ private: #endif #if ENABLED(COOLANT_CONTROL) - #if ENABLED(COOLANT_MIST) - static void M7(); - #endif - #if ENABLED(COOLANT_FLOOD) - static void M8(); - #endif + TERN_(COOLANT_MIST, static void M7()); + TERN_(COOLANT_FLOOD, static void M8()); static void M9(); #endif - #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) - static void M12(); - #endif + TERN_(EXTERNAL_CLOSED_LOOP_CONTROLLER, static void M12()); - #if ENABLED(EXPECTED_PRINTER_CHECK) - static void M16(); - #endif + TERN_(EXPECTED_PRINTER_CHECK, static void M16()); static void M17(); @@ -549,9 +517,7 @@ private: #if ENABLED(SDSUPPORT) static void M32(); - #if ENABLED(LONG_FILENAME_HOST_SUPPORT) - static void M33(); - #endif + TERN_(LONG_FILENAME_HOST_SUPPORT, static void M33()); #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) static void M34(); #endif @@ -559,29 +525,19 @@ private: static void M42(); - #if ENABLED(PINS_DEBUGGING) - static void M43(); - #endif + TERN_(PINS_DEBUGGING, static void M43()); - #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - static void M48(); - #endif + TERN_(Z_MIN_PROBE_REPEATABILITY_TEST, static void M48()); - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - static void M73(); - #endif + TERN_(LCD_SET_PROGRESS_MANUALLY, static void M73()); static void M75(); static void M76(); static void M77(); - #if ENABLED(PRINTCOUNTER) - static void M78(); - #endif + TERN_(PRINTCOUNTER, static void M78()); - #if ENABLED(PSU_CONTROL) - static void M80(); - #endif + TERN_(PSU_CONTROL, static void M80()); static void M81(); static void M82(); @@ -589,9 +545,7 @@ private: static void M85(); static void M92(); - #if ENABLED(M100_FREE_MEMORY_WATCHER) - static void M100(); - #endif + TERN_(M100_FREE_MEMORY_WATCHER, static void M100()); #if EXTRUDERS static void M104(); @@ -609,17 +563,13 @@ private: static void M108(); static void M112(); static void M410(); - #if ENABLED(HOST_PROMPT_SUPPORT) - static void M876(); - #endif + TERN_(HOST_PROMPT_SUPPORT, static void M876()); #endif static void M110(); static void M111(); - #if ENABLED(HOST_KEEPALIVE_FEATURE) - static void M113(); - #endif + TERN_(HOST_KEEPALIVE_FEATURE, static void M113()); static void M114(); static void M115(); @@ -629,9 +579,7 @@ private: static void M120(); static void M121(); - #if ENABLED(PARK_HEAD_ON_PAUSE) - static void M125(); - #endif + TERN_(PARK_HEAD_ON_PAUSE, static void M125()); #if ENABLED(BARICUDA) #if HAS_HEATER_1 @@ -658,13 +606,9 @@ private: static void M145(); #endif - #if ENABLED(TEMPERATURE_UNITS_SUPPORT) - static void M149(); - #endif + TERN_(TEMPERATURE_UNITS_SUPPORT, static void M149()); - #if HAS_COLOR_LEDS - static void M150(); - #endif + TERN_(HAS_COLOR_LEDS, static void M150()); #if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR static void M155(); @@ -673,12 +617,8 @@ private: #if ENABLED(MIXING_EXTRUDER) static void M163(); static void M164(); - #if ENABLED(DIRECT_MIXING_IN_G1) - static void M165(); - #endif - #if ENABLED(GRADIENT_MIX) - static void M166(); - #endif + TERN_(DIRECT_MIXING_IN_G1, static void M165()); + TERN_(GRADIENT_MIX, static void M166()); #endif static void M200(); @@ -692,16 +632,12 @@ private: static void M204(); static void M205(); - #if HAS_M206_COMMAND - static void M206(); - #endif + TERN_(HAS_M206_COMMAND, static void M206()); #if ENABLED(FWRETRACT) static void M207(); static void M208(); - #if ENABLED(FWRETRACT_AUTORETRACT) - static void M209(); - #endif + TERN_(FWRETRACT_AUTORETRACT, static void M209()); #endif static void M211(); @@ -710,9 +646,7 @@ private: static void M217(); #endif - #if HAS_HOTEND_OFFSET - static void M218(); - #endif + TERN_(HAS_HOTEND_OFFSET, static void M218()); static void M220(); @@ -722,13 +656,9 @@ private: static void M226(); - #if ENABLED(PHOTO_GCODE) - static void M240(); - #endif + TERN_(PHOTO_GCODE, static void M240()); - #if HAS_LCD_CONTRAST - static void M250(); - #endif + TERN_(HAS_LCD_CONTRAST, static void M250()); #if ENABLED(EXPERIMENTAL_I2CBUS) static void M260(); @@ -737,47 +667,29 @@ private: #if HAS_SERVOS static void M280(); - #if ENABLED(EDITABLE_SERVO_ANGLES) - static void M281(); - #endif + TERN_(EDITABLE_SERVO_ANGLES, static void M281()); #endif - #if ENABLED(BABYSTEPPING) - static void M290(); - #endif + TERN_(BABYSTEPPING, static void M290()); - #if HAS_BUZZER - static void M300(); - #endif + TERN_(HAS_BUZZER, static void M300()); - #if ENABLED(PIDTEMP) - static void M301(); - #endif + TERN_(PIDTEMP, static void M301()); - #if ENABLED(PREVENT_COLD_EXTRUSION) - static void M302(); - #endif + TERN_(PREVENT_COLD_EXTRUSION, static void M302()); - #if HAS_PID_HEATING - static void M303(); - #endif + TERN_(HAS_PID_HEATING, static void M303()); - #if ENABLED(PIDTEMPBED) - static void M304(); - #endif + TERN_(PIDTEMPBED, static void M304()); - #if HAS_USER_THERMISTORS - static void M305(); - #endif + TERN_(HAS_USER_THERMISTORS, static void M305()); #if HAS_MICROSTEPS static void M350(); static void M351(); #endif - #if HAS_CASE_LIGHT - static void M355(); - #endif + TERN_(HAS_CASE_LIGHT, static void M355()); #if ENABLED(MORGAN_SCARA) static bool M360(); @@ -799,9 +711,7 @@ private: static void M402(); #endif - #if ENABLED(PRUSA_MMU2) - static void M403(); - #endif + TERN_(PRUSA_MMU2, static void M403()); #if ENABLED(FILAMENT_WIDTH_SENSOR) static void M404(); @@ -810,26 +720,18 @@ private: static void M407(); #endif - #if HAS_FILAMENT_SENSOR - static void M412(); - #endif + TERN_(HAS_FILAMENT_SENSOR, static void M412()); #if HAS_LEVELING static void M420(); static void M421(); #endif - #if ENABLED(BACKLASH_GCODE) - static void M425(); - #endif + TERN_(BACKLASH_GCODE, static void M425()); - #if HAS_M206_COMMAND - static void M428(); - #endif + TERN_(HAS_M206_COMMAND, static void M428()); - #if ENABLED(CANCEL_OBJECTS) - static void M486(); - #endif + TERN_(CANCEL_OBJECTS, static void M486()); static void M500(); static void M501(); @@ -837,34 +739,22 @@ private: #if DISABLED(DISABLE_M503) static void M503(); #endif - #if ENABLED(EEPROM_SETTINGS) - static void M504(); - #endif + TERN_(EEPROM_SETTINGS, static void M504()); - #if ENABLED(SDSUPPORT) - static void M524(); - #endif + TERN_(SDSUPPORT, static void M524()); - #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) - static void M540(); - #endif + TERN_(SD_ABORT_ON_ENDSTOP_HIT, static void M540()); - #if ENABLED(BAUD_RATE_GCODE) - static void M575(); - #endif + TERN_(BAUD_RATE_GCODE, static void M575()); #if ENABLED(ADVANCED_PAUSE_FEATURE) static void M600(); static void M603(); #endif - #if HAS_DUPLICATION_MODE - static void M605(); - #endif + TERN_(HAS_DUPLICATION_MODE, static void M605()); - #if IS_KINEMATIC - static void M665(); - #endif + TERN_(IS_KINEMATIC, static void M665()); #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS static void M666(); @@ -879,17 +769,11 @@ private: static void M702(); #endif - #if ENABLED(GCODE_MACROS) - static void M810_819(); - #endif + TERN_(GCODE_MACROS, static void M810_819()); - #if HAS_BED_PROBE - static void M851(); - #endif + TERN_(HAS_BED_PROBE, static void M851()); - #if ENABLED(SKEW_CORRECTION_GCODE) - static void M852(); - #endif + TERN_(SKEW_CORRECTION_GCODE, static void M852()); #if ENABLED(I2C_POSITION_ENCODERS) FORCE_INLINE static void M860() { I2CPEM.M860(); } @@ -904,30 +788,20 @@ private: FORCE_INLINE static void M869() { I2CPEM.M869(); } #endif - #if ENABLED(PROBE_TEMP_COMPENSATION) - static void M871(); - #endif + TERN_(PROBE_TEMP_COMPENSATION, static void M871()); - #if ENABLED(LIN_ADVANCE) - static void M900(); - #endif + TERN_(LIN_ADVANCE, static void M900()); #if HAS_TRINAMIC_CONFIG static void M122(); static void M906(); - #if HAS_STEALTHCHOP - static void M569(); - #endif + TERN_(HAS_STEALTHCHOP, static void M569()); #if ENABLED(MONITOR_DRIVER_STATUS) static void M911(); static void M912(); #endif - #if ENABLED(HYBRID_THRESHOLD) - static void M913(); - #endif - #if USE_SENSORLESS - static void M914(); - #endif + TERN_(HYBRID_THRESHOLD, static void M913()); + TERN_(USE_SENSORLESS, static void M914()); #endif #if HAS_L64XX @@ -949,17 +823,11 @@ private: #endif #endif - #if ENABLED(SDSUPPORT) - static void M928(); - #endif + TERN_(SDSUPPORT, static void M928()); - #if ENABLED(MAGNETIC_PARKING_EXTRUDER) - static void M951(); - #endif + TERN_(MAGNETIC_PARKING_EXTRUDER, static void M951()); - #if ENABLED(PLATFORM_M997_SUPPORT) - static void M997(); - #endif + TERN_(PLATFORM_M997_SUPPORT, static void M997()); static void M999(); @@ -968,17 +836,11 @@ private: static void M1000(); #endif - #if ENABLED(SDSUPPORT) - static void M1001(); - #endif + TERN_(SDSUPPORT, static void M1001()); - #if ENABLED(MAX7219_GCODE) - static void M7219(); - #endif + TERN_(MAX7219_GCODE, static void M7219()); - #if ENABLED(CONTROLLER_FAN_EDITABLE) - static void M710(); - #endif + TERN_(CONTROLLER_FAN_EDITABLE, static void M710()); static void T(const uint8_t tool_index); diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index ec5b950b64..2e6fff7182 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -213,8 +213,6 @@ void GcodeSuite::M114() { if (parser.seen('R')) { report_real_position(); return; } #endif - #if ENABLED(M114_LEGACY) - planner.synchronize(); - #endif + TERN_(M114_LEGACY, planner.synchronize()); report_current_position_projected(); } diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index d74f909c47..2be95da0c7 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -44,14 +44,10 @@ void GcodeSuite::M115() { #if ENABLED(EXTENDED_CAPABILITIES_REPORT) // PAREN_COMMENTS - #if ENABLED(PAREN_COMMENTS) - cap_line(PSTR("PAREN_COMMENTS"), true); - #endif + TERN_(PAREN_COMMENTS, cap_line(PSTR("PAREN_COMMENTS"), true)); // QUOTED_STRINGS - #if ENABLED(GCODE_QUOTED_STRINGS) - cap_line(PSTR("QUOTED_STRINGS"), true); - #endif + TERN_(GCODE_QUOTED_STRINGS, cap_line(PSTR("QUOTED_STRINGS"), true)); // SERIAL_XON_XOFF cap_line(PSTR("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF)); @@ -92,7 +88,7 @@ void GcodeSuite::M115() { // CASE LIGHTS (M355) cap_line(PSTR("TOGGLE_LIGHTS"), ENABLED(HAS_CASE_LIGHT)); - cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN(HAS_CASE_LIGHT, PWM_PIN(CASE_LIGHT_PIN), 0)); + cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN0(HAS_CASE_LIGHT, PWM_PIN(CASE_LIGHT_PIN))); // EMERGENCY_PARSER (M108, M112, M410, M876) cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 190023b090..d39578ca76 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -77,15 +77,11 @@ void GcodeSuite::M0_M1() { #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR)); wait_for_user_response(ms); - #if HAS_LCD_MENU - ui.reset_status(); - #endif + TERN_(HAS_LCD_MENU, ui.reset_status()); } #endif // HAS_RESUME_CONTINUE diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index d6b18bdd95..1e8365d6d2 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -70,14 +70,12 @@ void plan_arc( ab_float_t rvec = -offset; const float radius = HYPOT(rvec.a, rvec.b), - #if ENABLED(AUTO_BED_LEVELING_UBL) - start_L = current_position[l_axis], - #endif center_P = current_position[p_axis] - rvec.a, center_Q = current_position[q_axis] - rvec.b, rt_X = cart[p_axis] - center_P, rt_Y = cart[q_axis] - center_Q, - linear_travel = cart[l_axis] - current_position[l_axis], + start_L = current_position[l_axis], + linear_travel = cart[l_axis] - start_L, extruder_travel = cart.e - current_position.e; // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. @@ -157,7 +155,6 @@ void plan_arc( // Initialize the extruder axis raw.e = current_position.e; - #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / seg_length; #endif @@ -220,15 +217,12 @@ void plan_arc( #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif - )) - break; + )) break; } // Ensure last segment arrives at target location. raw = cart; - #if ENABLED(AUTO_BED_LEVELING_UBL) - raw[l_axis] = start_L; - #endif + TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); apply_motion_limits(raw); @@ -242,10 +236,9 @@ void plan_arc( #endif ); - #if ENABLED(AUTO_BED_LEVELING_UBL) - raw[l_axis] = start_L; - #endif + TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); current_position = raw; + } // plan_arc /** @@ -285,9 +278,7 @@ void GcodeSuite::G2_G3(const bool clockwise) { get_destination_from_command(); // Get X Y Z E F (and set cutter power) - #if ENABLED(SF_ARC_FIX) - relative_mode = relative_mode_backup; - #endif + TERN_(SF_ARC_FIX, relative_mode = relative_mode_backup); ab_float_t arc_offset = { 0, 0 }; if (parser.seenval('R')) { diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 4ece6ede46..9a2272e747 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -83,9 +83,7 @@ void GCodeParser::reset() { string_arg = nullptr; // No whole line argument command_letter = '?'; // No command letter codenum = 0; // No command code - #if ENABLED(USE_GCODE_SUBCODES) - subcode = 0; // No command sub-code - #endif + TERN_(USE_GCODE_SUBCODES, subcode = 0); // No command sub-code #if ENABLED(FASTER_GCODE_PARSER) codebits = 0; // No codes yet //ZERO(param); // No parameters (should be safe to comment out this line) @@ -119,9 +117,8 @@ void GCodeParser::parse(char *p) { reset(); // No codes to report auto uppercase = [](char c) { - #if ENABLED(GCODE_CASE_INSENSITIVE) - if (WITHIN(c, 'a', 'z')) c += 'A' - 'a'; - #endif + if (TERN0(GCODE_CASE_INSENSITIVE, WITHIN(c, 'a', 'z'))) + c += 'A' - 'a'; return c; }; @@ -130,9 +127,7 @@ void GCodeParser::parse(char *p) { // Skip N[-0-9] if included in the command line if (uppercase(*p) == 'N' && NUMERIC_SIGNED(p[1])) { - #if ENABLED(FASTER_GCODE_PARSER) - //set('N', p + 1); // (optional) Set the 'N' parameter value - #endif + //TERN_(FASTER_GCODE_PARSER, set('N', p + 1)); // (optional) Set the 'N' parameter value p += 2; // skip N[-0-9] while (NUMERIC(*p)) ++p; // skip [0-9]* while (*p == ' ') ++p; // skip [ ]* @@ -213,9 +208,7 @@ void GCodeParser::parse(char *p) { ) ) { motion_mode_codenum = codenum; - #if ENABLED(USE_GCODE_SUBCODES) - motion_mode_subcode = subcode; - #endif + TERN_(USE_GCODE_SUBCODES, motion_mode_subcode = subcode); } #endif @@ -232,9 +225,7 @@ void GCodeParser::parse(char *p) { if (motion_mode_codenum < 0) return; command_letter = 'G'; codenum = motion_mode_codenum; - #if ENABLED(USE_GCODE_SUBCODES) - subcode = motion_mode_subcode; - #endif + TERN_(USE_GCODE_SUBCODES, subcode = motion_mode_subcode); p--; // Back up one character to use the current parameter break; #endif // GCODE_MOTION_MODES @@ -331,13 +322,9 @@ void GCodeParser::parse(char *p) { #endif } - #if ENABLED(DEBUG_GCODE_PARSER) - if (debug) SERIAL_EOL(); - #endif + if (TERN0(DEBUG_GCODE_PARSER, debug)) SERIAL_EOL(); - #if ENABLED(FASTER_GCODE_PARSER) - set(param, valptr); // Set parameter exists and pointer (nullptr for no value) - #endif + TERN_(FASTER_GCODE_PARSER, set(param, valptr)); // Set parameter exists and pointer (nullptr for no value) } else if (!string_arg) { // Not A-Z? First time, keep as the string_arg string_arg = p - 1; diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 21d56b3fd4..5a01289dea 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -46,9 +46,7 @@ void GcodeSuite::G30() { if (!probe.can_reach(pos)) return; // Disable leveling so the planner won't mess with us - #if HAS_LEVELING - set_bed_leveling_enabled(false); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); remember_feedrate_scaling_off(); diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp index c7e4ea8a70..cc94e70c93 100644 --- a/Marlin/src/gcode/probe/M951.cpp +++ b/Marlin/src/gcode/probe/M951.cpp @@ -46,9 +46,7 @@ void mpe_settings_init() { mpe_settings.parking_xpos[0] = pex[0]; // M951 L mpe_settings.parking_xpos[1] = pex[1]; // M951 R mpe_settings.grab_distance = PARKING_EXTRUDER_GRAB_DISTANCE; // M951 I - #if HAS_HOME_OFFSET - set_home_offset(X_AXIS, mpe_settings.grab_distance * -1); - #endif + TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1)); mpe_settings.slow_feedrate = MMM_TO_MMS(MPE_SLOW_SPEED); // M951 J mpe_settings.fast_feedrate = MMM_TO_MMS(MPE_FAST_SPEED); // M951 H mpe_settings.travel_distance = MPE_TRAVEL_DISTANCE; // M951 D @@ -61,9 +59,7 @@ void GcodeSuite::M951() { if (parser.seenval('R')) mpe_settings.parking_xpos[1] = parser.value_linear_units(); if (parser.seenval('I')) { mpe_settings.grab_distance = parser.value_linear_units(); - #if HAS_HOME_OFFSET - set_home_offset(X_AXIS, mpe_settings.grab_distance * -1); - #endif + TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1)); } if (parser.seenval('J')) mpe_settings.slow_feedrate = MMM_TO_MMS(parser.value_linear_units()); if (parser.seenval('H')) mpe_settings.fast_feedrate = MMM_TO_MMS(parser.value_linear_units()); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 43272e7835..7c4dc08486 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -127,9 +127,7 @@ void GCodeQueue::_commit_command(bool say_ok #if NUM_SERIAL > 1 port[index_w] = p; #endif - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.commit_sdpos(index_w); - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.commit_sdpos(index_w)); if (++index_w >= BUFSIZE) index_w = 0; length++; } @@ -522,9 +520,7 @@ void GCodeQueue::get_serial_commands() { // Process critical commands early if (strcmp(command, "M108") == 0) { wait_for_heatup = false; - #if HAS_LCD_MENU - wait_for_user = false; - #endif + TERN_(HAS_LCD_MENU, wait_for_user = false); } if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true); if (strcmp(command, "M410") == 0) quickstop_stepper(); @@ -601,9 +597,7 @@ void GCodeQueue::get_available_commands() { get_serial_commands(); - #if ENABLED(SDSUPPORT) - get_sdcard_commands(); - #endif + TERN_(SDSUPPORT, get_sdcard_commands()); } /** diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 26c51550ca..e5082be31f 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -72,14 +72,10 @@ void GcodeSuite::M1001() { gcode.process_subcommands_now_P(PSTR("M77")); // Set the progress bar "done" state - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - ui.set_progress_done(); - #endif + TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress_done()); // Purge the recovery file - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.purge(); - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.purge()); // Announce SD file completion SERIAL_ECHOLNPGM(STR_FILE_PRINTED); @@ -88,12 +84,8 @@ void GcodeSuite::M1001() { #if HAS_LEDS_OFF_FLAG if (long_print) { printerEventLEDs.onPrintCompleted(); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE)); - #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR)); wait_for_user_response(1000UL * TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)); printerEventLEDs.onResumeAfterWait(); } @@ -105,9 +97,7 @@ void GcodeSuite::M1001() { #endif // Re-select the last printed file in the UI - #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) - ui.reselect_last_file(); - #endif + TERN_(SD_REPRINT_LAST_SELECTED_FILE, ui.reselect_last_file()); } #endif // SDSUPPORT diff --git a/Marlin/src/gcode/sd/M23.cpp b/Marlin/src/gcode/sd/M23.cpp index 4bf8105f60..8cd9a33689 100644 --- a/Marlin/src/gcode/sd/M23.cpp +++ b/Marlin/src/gcode/sd/M23.cpp @@ -38,9 +38,7 @@ void GcodeSuite::M23() { for (char *fn = parser.string_arg; *fn; ++fn) if (*fn == ' ') *fn = '\0'; card.openFileRead(parser.string_arg); - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - ui.set_progress(0); - #endif + TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(0)); } #endif // SDSUPPORT diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index c1e6dde8de..ea1252885c 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -64,18 +64,14 @@ void GcodeSuite::M24() { if (card.isFileOpen()) { card.startFileprint(); // SD card will now be read for commands startOrResumeJob(); // Start (or resume) the print job timer - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.prepare(); - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); } #if ENABLED(HOST_ACTION_COMMANDS) #ifdef ACTION_ON_RESUME host_action_resume(); #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_open(PROMPT_INFO, PSTR("Resuming SD"), DISMISS_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming SD"), DISMISS_STR)); #endif ui.reset_status(); @@ -105,9 +101,7 @@ void GcodeSuite::M25() { ui.reset_status(); #if ENABLED(HOST_ACTION_COMMANDS) - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume"))); #ifdef ACTION_ON_PAUSE host_action_pause(); #endif diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index 434c6c9663..eec97df9e6 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -87,9 +87,7 @@ void GcodeSuite::M104() { #endif } - #if ENABLED(AUTOTEMP) - planner.autotemp_M104_M109(); - #endif + TERN_(AUTOTEMP, planner.autotemp_M104_M109()); } /** @@ -139,9 +137,7 @@ void GcodeSuite::M109() { #endif } - #if ENABLED(AUTOTEMP) - planner.autotemp_M104_M109(); - #endif + TERN_(AUTOTEMP, planner.autotemp_M104_M109()); if (set_temp) (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index b0739a8692..394ce2de17 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -76,9 +76,7 @@ void GcodeSuite::M190() { const bool no_wait_for_cooling = parser.seenval('S'); if (no_wait_for_cooling || parser.seenval('R')) { thermalManager.setTargetBed(parser.value_celsius()); - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - thermalManager.check_timer_autostart(true, false); - #endif + TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.check_timer_autostart(true, false)); } else return; diff --git a/Marlin/src/gcode/temp/M141_M191.cpp b/Marlin/src/gcode/temp/M141_M191.cpp index d76ba56c95..772bfe402b 100644 --- a/Marlin/src/gcode/temp/M141_M191.cpp +++ b/Marlin/src/gcode/temp/M141_M191.cpp @@ -75,9 +75,7 @@ void GcodeSuite::M191() { const bool no_wait_for_cooling = parser.seenval('S'); if (no_wait_for_cooling || parser.seenval('R')) { thermalManager.setTargetChamber(parser.value_celsius()); - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - thermalManager.check_timer_autostart(true, false); - #endif + TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.check_timer_autostart(true, false)); } else return; diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 358a1436b1..ab1781f3f5 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -72,9 +72,7 @@ void GcodeSuite::M303() { const heater_ind_t e = (heater_ind_t)parser.intval('E'); if (!WITHIN(e, SI, EI)) { SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); return; } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index ac44e832d6..626d353e38 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -431,7 +431,9 @@ #elif ENABLED(MIXING_EXTRUDER) #define E_STEPPERS MIXING_STEPPERS #define E_MANUAL 1 - #define DUAL_MIXING_EXTRUDER (MIXING_STEPPERS == 2) + #if MIXING_STEPPERS == 2 + #define HAS_DUAL_MIXING 1 + #endif #elif ENABLED(SWITCHING_TOOLHEAD) #define E_STEPPERS EXTRUDERS #define E_MANUAL EXTRUDERS diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index e8279475c7..bb42c39665 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -399,7 +399,9 @@ #define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_6 == (n) || TEMP_SENSOR_7 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n)) -#define HAS_USER_THERMISTORS ANY_TEMP_SENSOR_IS(1000) +#if ANY_TEMP_SENSOR_IS(1000) + #define HAS_USER_THERMISTORS 1 +#endif #if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 #define HEATER_0_USES_MAX6675 @@ -1269,7 +1271,7 @@ #define HAS_X_STEP 1 #endif #if PIN_EXISTS(X_MS1) - #define HAS_X_MICROSTEPS 1 + #define HAS_X_MS_PINS 1 #endif #if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)) @@ -1282,7 +1284,7 @@ #define HAS_X2_STEP 1 #endif #if PIN_EXISTS(X2_MS1) - #define HAS_X2_MICROSTEPS 1 + #define HAS_X2_MS_PINS 1 #endif #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) @@ -1295,7 +1297,7 @@ #define HAS_Y_STEP 1 #endif #if PIN_EXISTS(Y_MS1) - #define HAS_Y_MICROSTEPS 1 + #define HAS_Y_MS_PINS 1 #endif #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) @@ -1308,7 +1310,7 @@ #define HAS_Y2_STEP 1 #endif #if PIN_EXISTS(Y2_MS1) - #define HAS_Y2_MICROSTEPS 1 + #define HAS_Y2_MS_PINS 1 #endif #if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) @@ -1321,7 +1323,7 @@ #define HAS_Z_STEP 1 #endif #if PIN_EXISTS(Z_MS1) - #define HAS_Z_MICROSTEPS 1 + #define HAS_Z_MS_PINS 1 #endif #if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) @@ -1334,7 +1336,7 @@ #define HAS_Z2_STEP 1 #endif #if PIN_EXISTS(Z2_MS1) - #define HAS_Z2_MICROSTEPS 1 + #define HAS_Z2_MS_PINS 1 #endif #if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) @@ -1347,7 +1349,7 @@ #define HAS_Z3_STEP 1 #endif #if PIN_EXISTS(Z3_MS1) - #define HAS_Z3_MICROSTEPS 1 + #define HAS_Z3_MS_PINS 1 #endif #if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) @@ -1360,7 +1362,7 @@ #define HAS_Z4_STEP 1 #endif #if PIN_EXISTS(Z4_MS1) - #define HAS_Z4_MICROSTEPS 1 + #define HAS_Z4_MS_PINS 1 #endif // Extruder steppers and solenoids @@ -1374,7 +1376,7 @@ #define HAS_E0_STEP 1 #endif #if PIN_EXISTS(E0_MS1) - #define HAS_E0_MICROSTEPS 1 + #define HAS_E0_MS_PINS 1 #endif #if PIN_EXISTS(SOL0) #define HAS_SOLENOID_0 1 @@ -1390,7 +1392,7 @@ #define HAS_E1_STEP 1 #endif #if PIN_EXISTS(E1_MS1) - #define HAS_E1_MICROSTEPS 1 + #define HAS_E1_MS_PINS 1 #endif #if PIN_EXISTS(SOL1) #define HAS_SOLENOID_1 1 @@ -1406,7 +1408,7 @@ #define HAS_E2_STEP 1 #endif #if PIN_EXISTS(E2_MS1) - #define HAS_E2_MICROSTEPS 1 + #define HAS_E2_MS_PINS 1 #endif #if PIN_EXISTS(SOL2) #define HAS_SOLENOID_2 1 @@ -1422,7 +1424,7 @@ #define HAS_E3_STEP 1 #endif #if PIN_EXISTS(E3_MS1) - #define HAS_E3_MICROSTEPS 1 + #define HAS_E3_MS_PINS 1 #endif #if PIN_EXISTS(SOL3) #define HAS_SOLENOID_3 1 @@ -1438,7 +1440,7 @@ #define HAS_E4_STEP 1 #endif #if PIN_EXISTS(E4_MS1) - #define HAS_E4_MICROSTEPS 1 + #define HAS_E4_MS_PINS 1 #endif #if PIN_EXISTS(SOL4) #define HAS_SOLENOID_4 1 @@ -1454,7 +1456,7 @@ #define HAS_E5_STEP 1 #endif #if PIN_EXISTS(E5_MS1) - #define HAS_E5_MICROSTEPS 1 + #define HAS_E5_MS_PINS 1 #endif #if PIN_EXISTS(SOL5) #define HAS_SOLENOID_5 1 @@ -1470,7 +1472,7 @@ #define HAS_E6_STEP 1 #endif #if PIN_EXISTS(E6_MS1) - #define HAS_E6_MICROSTEPS 1 + #define HAS_E6_MS_PINS 1 #endif #if PIN_EXISTS(SOL6) #define HAS_SOLENOID_6 1 @@ -1486,13 +1488,16 @@ #define HAS_E7_STEP 1 #endif #if PIN_EXISTS(E7_MS1) - #define HAS_E7_MICROSTEPS 1 + #define HAS_E7_MS_PINS 1 #endif #if PIN_EXISTS(SOL7) #define HAS_SOLENOID_7 1 #endif +// // Trinamic Stepper Drivers +// + #if HAS_TRINAMIC_CONFIG #if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E) #define STEALTHCHOP_ENABLED 1 @@ -1535,10 +1540,15 @@ #endif #endif -#define HAS_E_STEPPER_ENABLE (HAS_E_DRIVER(TMC2660) \ +#if (HAS_E_DRIVER(TMC2660) \ || ( E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != X_ENABLE_PIN \ - && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) \ -) + && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) ) + #define HAS_E_STEPPER_ENABLE 1 +#endif + +#if ANY_AXIS_HAS(SW_SERIAL) + #define HAS_TMC_SW_SERIAL 1 +#endif // // Endstops and bed probe @@ -1767,24 +1777,31 @@ #define HAS_AUTO_CHAMBER_FAN 1 #endif -#define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN) +#if HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN + #define HAS_AUTO_FAN 1 +#endif #define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN) -#if HAS_AUTO_FAN - #define AUTO_CHAMBER_IS_E (_FANOVERLAP(CHAMBER,0) || _FANOVERLAP(CHAMBER,1) || _FANOVERLAP(CHAMBER,2) || _FANOVERLAP(CHAMBER,3) || _FANOVERLAP(CHAMBER,4) || _FANOVERLAP(CHAMBER,5) || _FANOVERLAP(CHAMBER,6) || _FANOVERLAP(CHAMBER,7)) +#if HAS_AUTO_FAN && (_FANOVERLAP(CHAMBER,0) || _FANOVERLAP(CHAMBER,1) || _FANOVERLAP(CHAMBER,2) || _FANOVERLAP(CHAMBER,3) || _FANOVERLAP(CHAMBER,4) || _FANOVERLAP(CHAMBER,5) || _FANOVERLAP(CHAMBER,6) || _FANOVERLAP(CHAMBER,7)) + #define AUTO_CHAMBER_IS_E 1 #endif #if !HAS_TEMP_SENSOR #undef AUTO_REPORT_TEMPERATURES #endif -#define HAS_AUTO_REPORTING EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS) +#if EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS) + #define HAS_AUTO_REPORTING 1 +#endif #if !HAS_AUTO_CHAMBER_FAN || AUTO_CHAMBER_IS_E #undef AUTO_POWER_CHAMBER_FAN #endif // Other fans -#define HAS_FAN0 (PIN_EXISTS(FAN)) -#define _HAS_FAN(P) (PIN_EXISTS(FAN##P) && CONTROLLER_FAN_PIN != FAN##P##_PIN && E0_AUTO_FAN_PIN != FAN##P##_PIN && E1_AUTO_FAN_PIN != FAN##P##_PIN && E2_AUTO_FAN_PIN != FAN##P##_PIN && E3_AUTO_FAN_PIN != FAN##P##_PIN && E4_AUTO_FAN_PIN != FAN##P##_PIN && E5_AUTO_FAN_PIN != FAN##P##_PIN && E6_AUTO_FAN_PIN != FAN##P##_PIN && E7_AUTO_FAN_PIN != FAN##P##_PIN) +#if PIN_EXISTS(FAN) + #define HAS_FAN0 1 +#endif +#define _NOT_E_AUTO(N,F) (E##N##_AUTO_FAN_PIN != FAN##F##_PIN) +#define _HAS_FAN(F) (PIN_EXISTS(FAN##F) && CONTROLLER_FAN_PIN != FAN##F##_PIN && _NOT_E_AUTO(0,F) && _NOT_E_AUTO(1,F) && _NOT_E_AUTO(2,F) && _NOT_E_AUTO(3,F) && _NOT_E_AUTO(4,F) && _NOT_E_AUTO(5,F) && _NOT_E_AUTO(6,F) && _NOT_E_AUTO(7,F)) #if _HAS_FAN(1) #define HAS_FAN1 1 #endif @@ -1806,6 +1823,8 @@ #if _HAS_FAN(7) #define HAS_FAN7 1 #endif +#undef _NOT_E_AUTO +#undef _HAS_FAN #if PIN_EXISTS(CONTROLLER_FAN) #define HAS_CONTROLLER_FAN 1 #endif @@ -1866,13 +1885,13 @@ #define HAS_MOTOR_CURRENT_PWM 1 #endif -#if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS - #define HAS_SOME_Z_MICROSTEPS 1 +#if HAS_Z_MS_PINS || HAS_Z2_MS_PINS || HAS_Z3_MS_PINS || HAS_Z4_MS_PINS + #define HAS_SOME_Z_MS_PINS 1 #endif -#if HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS || HAS_E6_MICROSTEPS || HAS_E7_MICROSTEPS - #define HAS_SOME_E_MICROSTEPS 1 +#if HAS_E0_MS_PINS || HAS_E1_MS_PINS || HAS_E2_MS_PINS || HAS_E3_MS_PINS || HAS_E4_MS_PINS || HAS_E5_MS_PINS || HAS_E6_MS_PINS || HAS_E7_MS_PINS + #define HAS_SOME_E_MS_PINS 1 #endif -#if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS +#if HAS_X_MS_PINS || HAS_X2_MS_PINS || HAS_Y_MS_PINS || HAS_Y2_MS_PINS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MS_PINS #define HAS_MICROSTEPS 1 #endif @@ -2071,7 +2090,9 @@ /** * Part Cooling fan multipliexer */ -#define HAS_FANMUX PIN_EXISTS(FANMUX0) +#if PIN_EXISTS(FANMUX0) + #define HAS_FANMUX 1 +#endif /** * MIN/MAX fan PWM scaling diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 1b51154acf..223967f818 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2124,6 +2124,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #undef IS_EXTUI #undef IS_ULTIPANEL +#if 1 < ENABLED(LCD_SCREEN_ROT_0) + ENABLED(LCD_SCREEN_ROT_90) + ENABLED(LCD_SCREEN_ROT_180) + ENABLED(LCD_SCREEN_ROT_270) + #error "Please enable only one LCD_SCREEN_ROT_* option: 0, 90, 180, or 270." +#endif + /** * FYSETC Mini 12864 RGB backlighting required */ diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 905a72b053..ac4cd63322 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -802,7 +802,7 @@ void MarlinUI::draw_status_screen() { #else // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED) - #if DUAL_MIXING_EXTRUDER + #if HAS_DUAL_MIXING // Two-component mix / gradient instead of XY @@ -822,13 +822,9 @@ void MarlinUI::draw_status_screen() { sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(mixer_messages); - #else // !DUAL_MIXING_EXTRUDER + #else // !HAS_DUAL_MIXING - if (true - #if ENABLED(LCD_SHOW_E_TOTAL) - && !printingIsActive() - #endif - ) { + if (TERN1(LCD_SHOW_E_TOTAL, !printingIsActive())) { const xy_pos_t lpos = current_position.asLogical(); _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); lcd_put_wchar(' '); @@ -843,7 +839,7 @@ void MarlinUI::draw_status_screen() { #endif } - #endif // !DUAL_MIXING_EXTRUDER + #endif // !HAS_DUAL_MIXING #endif // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED) @@ -1073,46 +1069,22 @@ void MarlinUI::draw_status_screen() { static uint8_t ledsprev = 0; uint8_t leds = 0; - #if HAS_HEATED_BED - if (thermalManager.degTargetBed() > 0) leds |= LED_A; - #endif - - #if HAS_HOTEND - if (thermalManager.degTargetHotend(0) > 0) leds |= LED_B; - #endif + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) leds |= LED_A; + if (TERN0(HAS_HOTEND, thermalManager.degTargetHotend(0) > 0)) leds |= LED_B; #if FAN_COUNT > 0 - if (0 - #if HAS_FAN0 - || thermalManager.fan_speed[0] - #endif - #if HAS_FAN1 - || thermalManager.fan_speed[1] - #endif - #if HAS_FAN2 - || thermalManager.fan_speed[2] - #endif - #if HAS_FAN3 - || thermalManager.fan_speed[3] - #endif - #if HAS_FAN4 - || thermalManager.fan_speed[4] - #endif - #if HAS_FAN5 - || thermalManager.fan_speed[5] - #endif - #if HAS_FAN6 - || thermalManager.fan_speed[6] - #endif - #if HAS_FAN7 - || thermalManager.fan_speed[7] - #endif + if ( TERN0(HAS_FAN0, thermalManager.fan_speed[0]) + || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) + || TERN0(HAS_FAN2, thermalManager.fan_speed[2]) + || TERN0(HAS_FAN3, thermalManager.fan_speed[3]) + || TERN0(HAS_FAN4, thermalManager.fan_speed[4]) + || TERN0(HAS_FAN5, thermalManager.fan_speed[5]) + || TERN0(HAS_FAN6, thermalManager.fan_speed[6]) + || TERN0(HAS_FAN7, thermalManager.fan_speed[7]) ) leds |= LED_C; #endif // FAN_COUNT > 0 - #if HAS_MULTI_HOTEND - if (thermalManager.degTargetHotend(1) > 0) leds |= LED_C; - #endif + if (TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1) > 0)) leds |= LED_C; if (leds != ledsprev) { lcd.setBacklight(leds); diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 741f07330f..281bc81509 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -1731,16 +1731,36 @@ #endif #endif -#define DO_DRAW_LOGO (STATUS_LOGO_WIDTH && ENABLED(CUSTOM_STATUS_SCREEN_IMAGE)) -#define DO_DRAW_HOTENDS (HOTENDS > 0) -#define DO_DRAW_BED (HAS_HEATED_BED && HOTENDS <= 4) -#define DO_DRAW_CUTTER (HAS_CUTTER && !DO_DRAW_BED) -#define DO_DRAW_CHAMBER (HAS_TEMP_CHAMBER && STATUS_CHAMBER_WIDTH && HOTENDS <= 4) -#define DO_DRAW_FAN (HAS_FAN0 && STATUS_FAN_WIDTH && HOTENDS <= 4 && defined(STATUS_FAN_FRAMES)) - -#define ANIM_HOTEND (HOTENDS && ENABLED(STATUS_HOTEND_ANIM)) -#define ANIM_BED (DO_DRAW_BED && ENABLED(STATUS_BED_ANIM)) -#define ANIM_CHAMBER (DO_DRAW_CHAMBER && ENABLED(STATUS_CHAMBER_ANIM)) -#define ANIM_CUTTER (DO_DRAW_CUTTER && ENABLED(STATUS_CUTTER_ANIM)) - -#define ANIM_HBCC (ANIM_HOTEND || ANIM_BED || ANIM_CHAMBER || ANIM_CUTTER) +#if STATUS_LOGO_WIDTH && ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) + #define DO_DRAW_LOGO 1 +#endif +#if HOTENDS > 0 + #define DO_DRAW_HOTENDS 1 +#endif +#if HAS_HEATED_BED && HOTENDS <= 4 + #define DO_DRAW_BED 1 +#endif +#if HAS_CUTTER && !DO_DRAW_BED + #define DO_DRAW_CUTTER 1 +#endif +#if HAS_TEMP_CHAMBER && STATUS_CHAMBER_WIDTH && HOTENDS <= 4 + #define DO_DRAW_CHAMBER 1 +#endif +#if HAS_FAN0 && STATUS_FAN_WIDTH && HOTENDS <= 4 && defined(STATUS_FAN_FRAMES) + #define DO_DRAW_FAN 1 +#endif +#if HOTENDS && ENABLED(STATUS_HOTEND_ANIM) + #define ANIM_HOTEND 1 +#endif +#if DO_DRAW_BED && ENABLED(STATUS_BED_ANIM) + #define ANIM_BED 1 +#endif +#if DO_DRAW_CHAMBER && ENABLED(STATUS_CHAMBER_ANIM) + #define ANIM_CHAMBER 1 +#endif +#if DO_DRAW_CUTTER && ENABLED(STATUS_CUTTER_ANIM) + #define ANIM_CUTTER 1 +#endif +#if ANIM_HOTEND || ANIM_BED || ANIM_CHAMBER || ANIM_CUTTER + #define ANIM_HBCC 1 +#endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index f2703ead7a..537153208b 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -56,7 +56,7 @@ #include "../../module/printcounter.h" #endif -#if DUAL_MIXING_EXTRUDER +#if HAS_DUAL_MIXING #include "../../feature/mixing.h" #endif @@ -365,15 +365,11 @@ void MarlinUI::draw_status_screen() { #if ANIM_HOTEND HOTEND_LOOP() if (thermalManager.isHeatingHotend(e)) SBI(new_bits, HEATBIT_HOTEND + e); #endif - #if ANIM_BED - if (thermalManager.isHeatingBed()) SBI(new_bits, HEATBIT_BED); - #endif + if (TERN0(ANIM_BED, thermalManager.isHeatingBed())) SBI(new_bits, HEATBIT_BED); #if DO_DRAW_CHAMBER && HAS_HEATED_CHAMBER if (thermalManager.isHeatingChamber()) SBI(new_bits, HEATBIT_CHAMBER); #endif - #if ANIM_CUTTER - if (cutter.enabled()) SBI(new_bits, HEATBIT_CUTTER); - #endif + if (TERN0(ANIM_CUTTER, cutter.enabled())) SBI(new_bits, HEATBIT_CUTTER); heat_bits = new_bits; #endif @@ -555,14 +551,10 @@ void MarlinUI::draw_status_screen() { #endif // Heated Bed - #if DO_DRAW_BED - _draw_bed_status(blink); - #endif + TERN_(DO_DRAW_BED, _draw_bed_status(blink)); // Heated Chamber - #if DO_DRAW_CHAMBER - _draw_chamber_status(); - #endif + TERN_(DO_DRAW_CHAMBER, _draw_chamber_status()); // Fan, if a bitmap was provided #if DO_DRAW_FAN @@ -695,7 +687,7 @@ void MarlinUI::draw_status_screen() { u8g.setColorIndex(0); // white on black #endif - #if DUAL_MIXING_EXTRUDER + #if HAS_DUAL_MIXING // Two-component mix / gradient instead of XY diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 64c6711fe8..0342d73607 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -537,14 +537,9 @@ void ST7920_Lite_Status_Screen::draw_heat_icon(const bool whichIcon, const bool static struct { bool E1_show_target : 1; bool E2_show_target : 1; - #if HAS_HEATED_BED - bool bed_show_target : 1; - #endif + TERN_(HAS_HEATED_BED, bool bed_show_target : 1); } display_state = { - true, true - #if HAS_HEATED_BED - , true - #endif + true, true, TERN_(HAS_HEATED_BED, true) }; void ST7920_Lite_Status_Screen::draw_temps(uint8_t line, const int16_t temp, const int16_t target, bool showTarget, bool targetStateChange) { @@ -672,11 +667,7 @@ void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool // If position is unknown, flash the labels. const unsigned char alt_label = position_known ? 0 : (ui.get_blink() ? ' ' : 0); - if (true - #if ENABLED(LCD_SHOW_E_TOTAL) - && !printingIsActive() - #endif - ) { + if (TERN1(LCD_SHOW_E_TOTAL, !printingIsActive())) { write_byte(alt_label ? alt_label : 'X'); write_str(dtostrf(pos.x, -4, 0, str), 4); @@ -712,13 +703,8 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { #endif static uint16_t last_checksum = 0; const uint16_t checksum = blink ^ feedrate_perc ^ fs ^ extruder_1_target - #if HOTENDS > 1 - ^ extruder_2_target - #endif - #if HAS_HEATED_BED - ^ bed_target - #endif - ; + ^ TERN0(HAS_MULTI_HOTEND, extruder_2_target) + ^ TERN0(HAS_HEATED_BED, bed_target); if (last_checksum == checksum) return false; last_checksum = checksum; return true; @@ -741,12 +727,8 @@ void ST7920_Lite_Status_Screen::update_indicators(const bool forceUpdate) { #endif draw_extruder_1_temp(extruder_1_temp, extruder_1_target, forceUpdate); - #if HAS_MULTI_HOTEND - draw_extruder_2_temp(extruder_2_temp, extruder_2_target, forceUpdate); - #endif - #if HAS_HEATED_BED - draw_bed_temp(bed_temp, bed_target, forceUpdate); - #endif + TERN_(HAS_MULTI_HOTEND, draw_extruder_2_temp(extruder_2_temp, extruder_2_target, forceUpdate)); + TERN_(HAS_HEATED_BED, draw_bed_temp(bed_temp, bed_target, forceUpdate)); uint16_t spd = thermalManager.fan_speed[0]; @@ -761,9 +743,7 @@ void ST7920_Lite_Status_Screen::update_indicators(const bool forceUpdate) { // Update the fan and bed animations if (spd) draw_fan_icon(blink); - #if HAS_HEATED_BED - draw_heat_icon(bed_target > 0 && blink, bed_target > 0); - #endif + TERN_(HAS_HEATED_BED, draw_heat_icon(bed_target > 0 && blink, bed_target > 0)); } } @@ -813,9 +793,7 @@ void ST7920_Lite_Status_Screen::update_status_or_position(bool forceUpdate) { * If STATUS_EXPIRE_SECONDS is zero, only the status is shown. */ if (forceUpdate || status_changed()) { - #if ENABLED(STATUS_MESSAGE_SCROLLING) - ui.status_scroll_offset = 0; - #endif + TERN_(STATUS_MESSAGE_SCROLLING, ui.status_scroll_offset = 0); #if STATUS_EXPIRE_SECONDS countdown = ui.status_message[0] ? STATUS_EXPIRE_SECONDS : 0; #endif @@ -823,26 +801,20 @@ void ST7920_Lite_Status_Screen::update_status_or_position(bool forceUpdate) { blink_changed(); // Clear changed flag } #if !STATUS_EXPIRE_SECONDS - #if ENABLED(STATUS_MESSAGE_SCROLLING) - else if (blink_changed()) - draw_status_message(); - #endif + else if (TERN0(STATUS_MESSAGE_SCROLLING, blink_changed())) + draw_status_message(); #else else if (blink_changed()) { if (countdown > 1) { countdown--; - #if ENABLED(STATUS_MESSAGE_SCROLLING) - draw_status_message(); - #endif + TERN_(STATUS_MESSAGE_SCROLLING, draw_status_message()); } else if (countdown > 0) { if (position_changed()) { countdown--; forceUpdate = true; } - #if ENABLED(STATUS_MESSAGE_SCROLLING) - draw_status_message(); - #endif + TERN_(STATUS_MESSAGE_SCROLLING, draw_status_message()); } } diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index 0a7064f17a..736f7050e8 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -227,9 +227,7 @@ bool MarlinUI::detected() { return true; } } void MarlinUI::show_bootscreen() { - #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) - show_custom_bootscreen(); - #endif + TERN_(SHOW_CUSTOM_BOOTSCREEN, show_custom_bootscreen()); show_marlin_bootscreen(); } @@ -267,17 +265,11 @@ void MarlinUI::init_lcd() { WRITE(LCD_BACKLIGHT_PIN, HIGH); #endif - #if HAS_LCD_CONTRAST - refresh_contrast(); - #endif + TERN_(HAS_LCD_CONTRAST, refresh_contrast()); - #if ENABLED(LCD_SCREEN_ROT_90) - u8g.setRot90(); - #elif ENABLED(LCD_SCREEN_ROT_180) - u8g.setRot180(); - #elif ENABLED(LCD_SCREEN_ROT_270) - u8g.setRot270(); - #endif + TERN_(LCD_SCREEN_ROT_90, u8g.setRot90()); + TERN_(LCD_SCREEN_ROT_180, u8g.setRot180()); + TERN_(LCD_SCREEN_ROT_270, u8g.setRot270()); #endif // !MKS_LCD12864B @@ -286,9 +278,7 @@ void MarlinUI::init_lcd() { // The kill screen is displayed for unrecoverable conditions void MarlinUI::draw_kill_screen() { - #if ENABLED(LIGHTWEIGHT_UI) - ST7920_Lite_Status_Screen::clear_text_buffer(); - #endif + TERN_(LIGHTWEIGHT_UI, ST7920_Lite_Status_Screen::clear_text_buffer()); const u8g_uint_t h4 = u8g.getHeight() / 4; u8g.firstPage(); do { diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index a04d8a8807..8bbbb231e2 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -734,9 +734,7 @@ void DGUSScreenVariableHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ switch (value) { default: break; case 1: - #if ENABLED(PRINTCOUNTER) - print_job_timer.initStats(); - #endif + TERN_(PRINTCOUNTER, print_job_timer.initStats()); queue.enqueue_now_P(PSTR("M502\nM500")); break; case 2: queue.enqueue_now_P(PSTR("M501")); break; @@ -958,17 +956,13 @@ void DGUSScreenVariableHandler::HandleHeaterControl(DGUS_VP_Variable &var, void #if HOTENDS >= 1 case VP_E0_BED_PREHEAT: thermalManager.setTargetHotend(e_temp, 0); - #if HAS_HEATED_BED - thermalManager.setTargetBed(bed_temp); - #endif + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); break; #endif #if HOTENDS >= 2 case VP_E1_BED_PREHEAT: thermalManager.setTargetHotend(e_temp, 1); - #if HAS_HEATED_BED - thermalManager.setTargetBed(bed_temp); - #endif + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); break; #endif } @@ -1002,9 +996,7 @@ void DGUSScreenVariableHandler::HandleHeaterControl(DGUS_VP_Variable &var, void #endif break; case 1: // Load ABS - #if ENABLED(PREHEAT_2_TEMP_HOTEND) - e_temp = PREHEAT_2_TEMP_HOTEND; - #endif + TERN_(PREHEAT_2_TEMP_HOTEND, e_temp = PREHEAT_2_TEMP_HOTEND); break; case 2: // Load PET #ifdef PREHEAT_3_TEMP_HOTEND @@ -1227,9 +1219,8 @@ bool DGUSScreenVariableHandler::loop() { #if ENABLED(SHOW_BOOTSCREEN) static bool booted = false; - #if ENABLED(POWER_LOSS_RECOVERY) - if (!booted && recovery.valid()) booted = true; - #endif + if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + booted = true; if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { booted = true; GotoScreen(DGUSLCD_SCREEN_MAIN); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index 59af72edaa..40676d6254 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -453,9 +453,7 @@ bool UIFlashStorage::is_present = false; if (nBytes != write_page_size) break; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::yield(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::yield()); } SERIAL_ECHOLNPGM("DONE"); @@ -493,9 +491,7 @@ bool UIFlashStorage::is_present = false; addr += nBytes; if (nBytes != write_page_size) break; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::yield(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::yield()); }; if (verifyOk) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index f57d2d896a..42ba64de7c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -922,9 +922,8 @@ template bool CLCD::CommandFifo::_write_unaligned(T data, uint16_t len uint32_t command_read_ptr; #if ENABLED(TOUCH_UI_DEBUG) - if (command_write_ptr == 0xFFFFFFFFul) { - SERIAL_ECHO_MSG("Attempt to write to FIFO before CommandFifo::Cmd_Start()."); - } + if (command_write_ptr == 0xFFFFFFFFul) + SERIAL_ECHO_MSG("Attempt to write to FIFO before CommandFifo::Cmd_Start()."); #endif /* Wait until there is enough space in the circular buffer for the transfer */ @@ -1160,24 +1159,15 @@ void CLCD::default_display_orientation() { // processor to do this since it will also update the transform matrices. if (FTDI::ftdi_chip >= 810) { CommandFifo cmd; - cmd.setrotate(0 - #if ENABLED(TOUCH_UI_MIRRORED) - + 4 - #endif - #if ENABLED(TOUCH_UI_PORTRAIT) - + 2 - #endif - #if ENABLED(TOUCH_UI_INVERTED) - + 1 - #endif + cmd.setrotate( + ENABLED(TOUCH_UI_MIRRORED) * 4 + + ENABLED(TOUCH_UI_PORTRAIT) * 2 + + ENABLED(TOUCH_UI_INVERTED) * 1 ); cmd.execute(); } - else { - #if ENABLED(TOUCH_UI_INVERTED) - mem_write_32(REG::ROTATE, 1); - #endif - } + else + TERN_(TOUCH_UI_INVERTED, mem_write_32(REG::ROTATE, 1)); #elif ANY(TOUCH_UI_PORTRAIT, TOUCH_UI_MIRRORED) #error "PORTRAIT or MIRRORED orientation not supported on the FT800." #elif ENABLED(TOUCH_UI_INVERTED) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 3023a1c6bc..8922f3eb3e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -206,14 +206,58 @@ // Define macros for compatibility - #define _CAT(a, ...) a ## __VA_ARGS__ - #define SWITCH_ENABLED_ 1 - #define ENABLED(b) _CAT(SWITCH_ENABLED_, b) - #define DISABLED(b) !ENABLED(b) - #define ANY(A,B) (ENABLED(A) || ENABLED(B)) - #define EITHER(A,B) (ENABLED(A) || ENABLED(B)) - #define BOTH(A,B) (ENABLED(A) && ENABLED(B)) - #define NONE(A,B) (DISABLED(A) && DISABLED(B)) + #define _CAT(a,V...) a##V + #define CAT(a,V...) _CAT(a,V) + + #define FIRST(a,...) a + #define SECOND(a,b,...) b + #define THIRD(a,b,c,...) c + + #define IS_PROBE(V...) SECOND(V, 0) // Get the second item passed, or 0 + #define PROBE() ~, 1 // Second item will be 1 if this is passed + #define _NOT_0 PROBE() + #define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'. + #define _BOOL(x) NOT(NOT(x)) // NOT('0') gets '0'. Anything else gets '1'. + + #define _DO_1(W,C,A) (_##W##_1(A)) + #define _DO_2(W,C,A,B) (_##W##_1(A) C _##W##_1(B)) + #define _DO_3(W,C,A,V...) (_##W##_1(A) C _DO_2(W,C,V)) + #define _DO_4(W,C,A,V...) (_##W##_1(A) C _DO_3(W,C,V)) + #define _DO_5(W,C,A,V...) (_##W##_1(A) C _DO_4(W,C,V)) + #define _DO_6(W,C,A,V...) (_##W##_1(A) C _DO_5(W,C,V)) + #define _DO_7(W,C,A,V...) (_##W##_1(A) C _DO_6(W,C,V)) + #define _DO_8(W,C,A,V...) (_##W##_1(A) C _DO_7(W,C,V)) + #define _DO_9(W,C,A,V...) (_##W##_1(A) C _DO_8(W,C,V)) + #define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V)) + #define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V)) + #define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V)) + #define __DO_N(W,C,N,V...) _DO_##N(W,C,V) + #define _DO_N(W,C,N,V...) __DO_N(W,C,N,V) + #define DO(W,C,V...) _DO_N(W,C,NUM_ARGS(V),V) + + #define _ISENA_ ~,1 + #define _ISENA_1 ~,1 + #define _ISENA_0x1 ~,1 + #define _ISENA_true ~,1 + #define _ISENA(V...) IS_PROBE(V) + #define _ENA_1(O) _ISENA(CAT(_IS,CAT(ENA_, O))) + #define _DIS_1(O) NOT(_ENA_1(O)) + #define ENABLED(V...) DO(ENA,&&,V) + #define DISABLED(V...) DO(DIS,&&,V) + + #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' + #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' + #define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' + #define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' + #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' + #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' + #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. + + #define ANY(V...) !DISABLED(V) + #define NONE(V...) DISABLED(V) + #define ALL(V...) ENABLED(V) + #define BOTH(V1,V2) ALL(V1,V2) + #define EITHER(V1,V2) ANY(V1,V2) // Remove compiler warning on an unused variable #ifndef UNUSED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp index 7e88b7883a..9689170077 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp @@ -78,9 +78,7 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #if LCD_TIMEOUT_TO_STATUS - last_interaction = millis(); - #endif + TERN_(LCD_TIMEOUT_TO_STATUS, last_interaction = millis()); } #if LCD_TIMEOUT_TO_STATUS diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp index ec7f2bcffb..0a583d1cb8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp @@ -198,16 +198,14 @@ void StatusScreen::draw_temperature(draw_mode_t what) { void StatusScreen::draw_syringe(draw_mode_t what) { int16_t x, y, h, v; - #ifdef E_MAX_POS - const float fill_level = 1.0 - min(1.0, max(0.0, getAxisPosition_mm(E0) / E_MAX_POS)); - #else - const float fill_level = 0.75; - #endif - const bool e_homed = (true - #if ENABLED(TOUCH_UI_LULZBOT_BIO) - && isAxisPositionKnown(E0) + const float fill_level = ( + #ifdef E_MAX_POS + 1.0 - min(1.0, max(0.0, getAxisPosition_mm(E0) / E_MAX_POS)) + #else + 0.75 #endif ); + const bool e_homed = TERN0(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)); CommandProcessor cmd; PolyUI ui(cmd, what); @@ -237,12 +235,8 @@ void StatusScreen::draw_syringe(draw_mode_t what) { } void StatusScreen::draw_arrows(draw_mode_t what) { - const bool e_homed = (true - #if ENABLED(TOUCH_UI_LULZBOT_BIO) - && isAxisPositionKnown(E0) - #endif - ); - const bool z_homed = isAxisPositionKnown(Z); + const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)), + z_homed = isAxisPositionKnown(Z); CommandProcessor cmd; PolyUI ui(cmd, what); @@ -299,12 +293,8 @@ void StatusScreen::draw_fine_motion(draw_mode_t what) { } void StatusScreen::draw_overlay_icons(draw_mode_t what) { - const bool e_homed = (true - #if ENABLED(TOUCH_UI_LULZBOT_BIO) - && isAxisPositionKnown(E0) - #endif - ); - const bool z_homed = isAxisPositionKnown(Z); + const bool e_homed = TERN1(TOUCH_UI_LULZBOT_BIO, isAxisPositionKnown(E0)), + z_homed = isAxisPositionKnown(Z); CommandProcessor cmd; PolyUI ui(cmd, what); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp index 27312c733f..cb3827226b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp @@ -50,11 +50,7 @@ void TuneMenu::onRedraw(draw_mode_t what) { .font(font_medium) .enabled( isPrinting()).tag(2).button( BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_SPEED)) .tag(3).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) - .enabled( - #if ENABLED(BABYSTEPPING) - true - #endif - ) + .enabled(TERN_(BABYSTEPPING, true)) .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_NUDGE_NOZZLE)) .enabled(!isPrinting()).tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) .enabled(!isPrinting()).tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RAISE_PLUNGER)) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp index d32ec4d07f..654fdba0b2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp @@ -89,11 +89,7 @@ void FilesScreen::drawFileButton(const char* filename, uint8_t tag, bool is_dir, cmd.cmd(MACRO(0)); } #endif - cmd.text (BTN_POS(1,header_h+line), BTN_SIZE(6,1), filename, OPT_CENTERY - #if ENABLED(SCROLL_LONG_FILENAMES) - | OPT_NOFIT - #endif - ); + cmd.text (BTN_POS(1,header_h+line), BTN_SIZE(6,1), filename, OPT_CENTERY | TERN0(SCROLL_LONG_FILENAMES, OPT_NOFIT)); if (is_dir) { cmd.text(BTN_POS(1,header_h+line), BTN_SIZE(6,1), F("> "), OPT_CENTERY | OPT_RIGHTX); } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 325d0c07f2..401a1298c6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -252,9 +252,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { for(uint8_t i = 0; i < InterfaceSoundsScreen::NUM_EVENTS; i++) InterfaceSoundsScreen::event_sounds[i] = eeprom.event_sounds[i]; - #if ENABLED(TOUCH_UI_DEVELOPER_MENU) - StressTestScreen::startupCheck(); - #endif + TERN_(TOUCH_UI_DEVELOPER_MENU, StressTestScreen::startupCheck()); } #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp index 4025d16bbd..c647812a0a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp @@ -97,12 +97,8 @@ bool TemperatureScreen::onTouchHeld(uint8_t tag) { case 30: #define _HOTEND_OFF(N) setTargetTemp_celsius(0,E##N); REPEAT(HOTENDS, _HOTEND_OFF); - #if HAS_HEATED_BED - setTargetTemp_celsius(0,BED); - #endif - #if HAS_HEATED_CHAMBER - setTargetTemp_celsius(0,CHAMBER); - #endif + TERN_(HAS_HEATED_BED, setTargetTemp_celsius(0,BED)); + TERN_(HAS_HEATED_CHAMBER, setTargetTemp_celsius(0,CHAMBER)); #if FAN_COUNT > 0 setTargetFan_percent(0,FAN0); #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 55ae020616..b272d9d496 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -109,12 +109,8 @@ namespace ExtUI { static struct { uint8_t printer_killed : 1; - #if ENABLED(JOYSTICK) - uint8_t jogging : 1; - #endif - #if ENABLED(SDSUPPORT) - uint8_t was_sd_printing : 1; - #endif + TERN_(JOYSTICK, uint8_t jogging : 1); + TERN_(SDSUPPORT, uint8_t was_sd_printing : 1); } flags; #ifdef __SAM3X8E__ @@ -192,9 +188,7 @@ namespace ExtUI { case CHAMBER: return; // Chamber has no idle timer #endif default: - #if HAS_HOTEND - thermalManager.reset_hotend_idle_timer(heater - H0); - #endif + TERN_(HAS_HOTEND, thermalManager.reset_hotend_idle_timer(heater - H0)); break; } #else @@ -251,9 +245,7 @@ namespace ExtUI { bool isHeaterIdle(const heater_t heater) { #if HEATER_IDLE_HANDLER switch (heater) { - #if HAS_HEATED_BED - case BED: return thermalManager.bed_idle.timed_out; - #endif + TERN_(HAS_HEATED_BED, case BED: return thermalManager.bed_idle.timed_out); #if HAS_HEATED_CHAMBER case CHAMBER: return false; // Chamber has no idle timer #endif @@ -278,12 +270,8 @@ namespace ExtUI { float getActualTemp_celsius(const heater_t heater) { switch (heater) { - #if HAS_HEATED_BED - case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degBed()); - #endif - #if HAS_HEATED_CHAMBER - case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degChamber()); - #endif + TERN_(HAS_HEATED_BED, case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degBed())); + TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degChamber())); default: return GET_TEMP_ADJUSTMENT(thermalManager.degHotend(heater - H0)); } } @@ -294,12 +282,8 @@ namespace ExtUI { float getTargetTemp_celsius(const heater_t heater) { switch (heater) { - #if HAS_HEATED_BED - case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetBed()); - #endif - #if HAS_HEATED_CHAMBER - case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetChamber()); - #endif + TERN_(HAS_HEATED_BED, case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetBed())); + TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetChamber())); default: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetHotend(heater - H0)); } } @@ -356,28 +340,16 @@ namespace ExtUI { #if HAS_SOFTWARE_ENDSTOPS if (soft_endstops_enabled) switch (axis) { case X_AXIS: - #if ENABLED(MIN_SOFTWARE_ENDSTOP_X) - min = soft_endstop.min.x; - #endif - #if ENABLED(MAX_SOFTWARE_ENDSTOP_X) - max = soft_endstop.max.x; - #endif + TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x); + TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x); break; case Y_AXIS: - #if ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - min = soft_endstop.min.y; - #endif - #if ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - max = soft_endstop.max.y; - #endif + TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y); break; case Z_AXIS: - #if ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - min = soft_endstop.min.z; - #endif - #if ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - max = soft_endstop.max.z; - #endif + TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z); default: break; } #endif // HAS_SOFTWARE_ENDSTOPS @@ -541,15 +513,9 @@ namespace ExtUI { int getTMCBumpSensitivity(const axis_t axis) { switch (axis) { - #if X_SENSORLESS - case X: return stepperX.homing_threshold(); - #endif - #if Y_SENSORLESS - case Y: return stepperY.homing_threshold(); - #endif - #if Z_SENSORLESS - case Z: return stepperZ.homing_threshold(); - #endif + TERN_(X_SENSORLESS, case X: return stepperX.homing_threshold()); + TERN_(Y_SENSORLESS, case Y: return stepperY.homing_threshold()); + TERN_(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()); default: return 0; } } @@ -673,9 +639,7 @@ namespace ExtUI { void setJunctionDeviation_mm(const float value) { planner.junction_deviation_mm = constrain(value, 0.01, 0.3); - #if ENABLED(LIN_ADVANCE) - planner.recalculate_max_e_jerk(); - #endif + TERN_(LIN_ADVANCE, planner.recalculate_max_e_jerk()); } #else @@ -871,9 +835,7 @@ namespace ExtUI { void setMeshPoint(const xy_uint8_t &pos, const float zoff) { if (WITHIN(pos.x, 0, GRID_MAX_POINTS_X) && WITHIN(pos.y, 0, GRID_MAX_POINTS_Y)) { Z_VALUES(pos.x, pos.y) = zoff; - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif + TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); } } #endif @@ -1020,9 +982,7 @@ namespace ExtUI { } void setUserConfirmed() { - #if HAS_RESUME_CONTINUE - wait_for_user = false; - #endif + TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } void printFile(const char *filename) { diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 8880be7ef3..74e16fbdbc 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -51,21 +51,9 @@ namespace ExtUI { while (!ScreenHandler.loop()); // Wait while anything is left to be sent } - void onMediaInserted() { - #if ENABLED(SDSUPPORT) - ScreenHandler.SDCardInserted(); - #endif - } - void onMediaError() { - #if ENABLED(SDSUPPORT) - ScreenHandler.SDCardError(); - #endif - } - void onMediaRemoved() { - #if ENABLED(SDSUPPORT) - ScreenHandler.SDCardRemoved(); - #endif - } + void onMediaInserted() { TERN_(SDSUPPORT, ScreenHandler.SDCardInserted()); } + void onMediaError() { TERN_(SDSUPPORT, ScreenHandler.SDCardError()); } + void onMediaRemoved() { TERN_(SDSUPPORT, ScreenHandler.SDCardRemoved()); } void onPlayTone(const uint16_t frequency, const uint16_t duration) {} void onPrintTimerStarted() {} diff --git a/Marlin/src/lcd/menu/game/game.h b/Marlin/src/lcd/menu/game/game.h index 3ebee563de..a48c7b7461 100644 --- a/Marlin/src/lcd/menu/game/game.h +++ b/Marlin/src/lcd/menu/game/game.h @@ -53,18 +53,10 @@ // Pool game data to save SRAM union MarlinGameData { - #if ENABLED(MARLIN_BRICKOUT) - brickout_data_t brickout; - #endif - #if ENABLED(MARLIN_INVADERS) - invaders_data_t invaders; - #endif - #if ENABLED(MARLIN_SNAKE) - snake_data_t snake; - #endif - #if ENABLED(MARLIN_MAZE) - maze_data_t maze; - #endif + TERN_(MARLIN_BRICKOUT, brickout_data_t brickout); + TERN_(MARLIN_INVADERS, invaders_data_t invaders); + TERN_(MARLIN_SNAKE, snake_data_t snake); + TERN_(MARLIN_MAZE, maze_data_t maze); }; extern MarlinGameData marlin_game_data; diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 3dd9932044..1698c7d7ad 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -141,9 +141,7 @@ void MenuItem_gcode::action(PGM_P const, PGM_P const pgcode) { queue.inject_P(pg * MenuItem_int3::draw(encoderLine == _thisItemNr, _lcdLineNr, plabel, &feedrate_percentage, 10, 999) */ void MenuEditItemBase::edit_screen(strfunc_t strfunc, loadfunc_t loadfunc) { - #if ENABLED(TOUCH_BUTTONS) - ui.repeat_delay = BUTTON_DELAY_EDIT; - #endif + TERN_(TOUCH_BUTTONS, ui.repeat_delay = BUTTON_DELAY_EDIT); if (int32_t(ui.encoderPosition) < 0) ui.encoderPosition = 0; if (int32_t(ui.encoderPosition) > maxEditValue) ui.encoderPosition = maxEditValue; if (ui.should_draw()) @@ -222,13 +220,9 @@ bool printer_busy() { void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, const uint8_t top/*=0*/, const uint8_t items/*=0*/) { if (currentScreen != screen) { - #if ENABLED(TOUCH_BUTTONS) - repeat_delay = BUTTON_DELAY_MENU; - #endif + TERN_(TOUCH_BUTTONS, repeat_delay = BUTTON_DELAY_MENU); - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - progress_reset(); - #endif + TERN_(LCD_SET_PROGRESS_MANUALLY, progress_reset()); #if BOTH(DOUBLECLICK_FOR_Z_BABYSTEPPING, BABYSTEPPING) static millis_t doubleclick_expire_ms = 0; @@ -275,9 +269,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co screen_items = items; if (screen == status_screen) { defer_status_screen(false); - #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.lcd_map_control = false; - #endif + TERN_(AUTO_BED_LEVELING_UBL, ubl.lcd_map_control = false); screen_history_depth = 0; } @@ -294,13 +286,9 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co refresh(LCDVIEW_CALL_REDRAW_NEXT); screen_changed = true; - #if HAS_GRAPHICAL_LCD - drawing_screen = false; - #endif + TERN_(HAS_GRAPHICAL_LCD, drawing_screen = false); - #if HAS_LCD_MENU - encoder_direction_normal(); - #endif + TERN_(HAS_LCD_MENU, encoder_direction_normal()); set_selection(false); } @@ -400,10 +388,10 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { babystep.add_steps(Z_AXIS, babystep_increment); - if (do_probe) probe.offset.z = new_offs; - #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - else hotend_offset[active_extruder].z = new_offs; - #endif + if (do_probe) + probe.offset.z = new_offs; + else + TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); } @@ -415,9 +403,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #endif if (do_probe) { MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), BABYSTEP_TO_STR(probe.offset.z)); - #if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) - _lcd_zoffset_overlay_gfx(probe.offset.z); - #endif + TERN_(BABYSTEP_ZPROBE_GFX_OVERLAY, _lcd_zoffset_overlay_gfx(probe.offset.z)); } } } @@ -427,16 +413,12 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #if ENABLED(EEPROM_SETTINGS) void lcd_store_settings() { const bool saved = settings.save(); - #if HAS_BUZZER - ui.completion_feedback(saved); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback(saved)); UNUSED(saved); } void lcd_load_settings() { const bool loaded = settings.load(); - #if HAS_BUZZER - ui.completion_feedback(loaded); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback(loaded)); UNUSED(loaded); } #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index f0bbfdfed1..28d8411940 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -576,9 +576,7 @@ void menu_advanced_settings() { // const bool new_state = !settings.sd_update_status(), didset = settings.set_sd_update_status(new_state); - #if HAS_BUZZER - ui.completion_feedback(didset); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback(didset)); ui.return_to_status(); if (new_state) LCD_MESSAGEPGM(MSG_RESET_PRINTER); else ui.reset_status(); }); @@ -589,9 +587,7 @@ void menu_advanced_settings() { MSG_BUTTON_INIT, MSG_BUTTON_CANCEL, []{ const bool inited = settings.init_eeprom(); - #if HAS_BUZZER - ui.completion_feedback(inited); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback(inited)); UNUSED(inited); }, ui.goto_previous_screen, diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 3d0a5bf2aa..71eac08025 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -70,11 +70,7 @@ static inline void _lcd_goto_next_corner() { } line_to_current_position(manual_feedrate_mm_s.x); line_to_z(LEVEL_CORNERS_HEIGHT); - if (++bed_corner > (3 - #if ENABLED(LEVEL_CENTER_TOO) - + 1 - #endif - )) bed_corner = 0; + if (++bed_corner > 3 + ENABLED(LEVEL_CENTER_TOO)) bed_corner = 0; } static inline void _lcd_level_bed_corners_homing() { @@ -86,9 +82,7 @@ static inline void _lcd_level_bed_corners_homing() { GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE), _lcd_goto_next_corner, []{ - #if HAS_LEVELING - set_bed_leveling_enabled(leveling_was_active); - #endif + TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); ui.goto_previous_screen_no_defer(); }, GET_TEXT( diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 5834b73ba4..54a9cb5c23 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -75,9 +75,7 @@ ui.synchronize(GET_TEXT(MSG_LEVEL_BED_DONE)); #endif ui.goto_previous_screen_no_defer(); - #if HAS_BUZZER - ui.completion_feedback(); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback()); } if (ui.should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT(MSG_LEVEL_BED_DONE)); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index 4d445a1848..398dd10e2c 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -44,9 +44,7 @@ static void lcd_cancel_object_confirm() { MenuItem_confirm::confirm_screen( []{ cancelable.cancel_object(MenuItemBase::itemIndex - 1); - #if HAS_BUZZER - ui.completion_feedback(); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback()); ui.goto_previous_screen(); }, ui.goto_previous_screen, diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 6dbc680659..b0202198b7 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -421,9 +421,7 @@ void menu_configuration() { if (!busy) ACTION_ITEM(MSG_RESTORE_DEFAULTS, []{ settings.reset(); - #if HAS_BUZZER - ui.completion_feedback(); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback()); }); END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_custom.cpp b/Marlin/src/lcd/menu/menu_custom.cpp index 55297a8b92..6f27c907a6 100644 --- a/Marlin/src/lcd/menu/menu_custom.cpp +++ b/Marlin/src/lcd/menu/menu_custom.cpp @@ -42,9 +42,7 @@ void _lcd_user_gcode(PGM_P const cmd) { #if ENABLED(USER_SCRIPT_AUDIBLE_FEEDBACK) && HAS_BUZZER ui.completion_feedback(); #endif - #if ENABLED(USER_SCRIPT_RETURN) - ui.return_to_status(); - #endif + TERN_(USER_SCRIPT_RETURN, ui.return_to_status()); } void menu_user() { diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index ac80870ac8..d6639206bb 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -62,12 +62,8 @@ void _man_probe_pt(const xy_pos_t &xy) { float lcd_probe_pt(const xy_pos_t &xy) { _man_probe_pt(xy); ui.defer_status_screen(); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Delta Calibration in progress"), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Delta Calibration in progress"), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress"))); wait_for_user_response(); ui.goto_previous_screen_no_defer(); return current_position.z; @@ -102,9 +98,7 @@ void _man_probe_pt(const xy_pos_t &xy) { void lcd_delta_settings() { auto _recalc_delta_settings = []{ - #if HAS_LEVELING - reset_bed_level(); // After changing kinematics bed-level data is no longer valid - #endif + TERN_(HAS_LEVELING, reset_bed_level()); // After changing kinematics bed-level data is no longer valid recalc_delta_settings(); }; START_MENU(); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index b21cb7e556..4c17208b25 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -39,8 +39,12 @@ #include "game/game.h" #endif -#define MACHINE_CAN_STOP (EITHER(SDSUPPORT, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL)) -#define MACHINE_CAN_PAUSE (ANY(SDSUPPORT, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE)) +#if EITHER(SDSUPPORT, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL) + #define MACHINE_CAN_STOP 1 +#endif +#if ANY(SDSUPPORT, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE) + #define MACHINE_CAN_PAUSE 1 +#endif #if ENABLED(PRUSA_MMU2) #include "../../lcd/menu/menu_mmu2.h" @@ -140,9 +144,8 @@ void menu_main() { #endif // !HAS_ENCODER_WHEEL && SDSUPPORT - #if MACHINE_CAN_PAUSE - if (printingIsPaused()) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); - #endif + if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) + ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); SUBMENU(MSG_MOTION, menu_motion); } @@ -236,9 +239,7 @@ void menu_main() { #if HAS_SERVICE_INTERVALS static auto _service_reset = [](const int index) { print_job_timer.resetServiceInterval(index); - #if HAS_BUZZER - ui.completion_feedback(); - #endif + TERN_(HAS_BUZZER, ui.completion_feedback()); ui.reset_status(); ui.return_to_status(); }; diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 4e68894add..d818081f10 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -113,9 +113,7 @@ class MenuItem_sdfolder : public MenuItem_sdbase { encoderTopLine = 0; ui.encoderPosition = 2 * (ENCODER_STEPS_PER_MENU_ITEM); ui.screen_changed = true; - #if HAS_GRAPHICAL_LCD - ui.drawing_screen = false; - #endif + TERN_(HAS_GRAPHICAL_LCD, ui.drawing_screen = false); ui.refresh(); } }; diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index 7230320fa2..13c19f43fc 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -33,7 +33,7 @@ #include "../../feature/mixing.h" -#define CHANNEL_MIX_EDITING !DUAL_MIXING_EXTRUDER +#define CHANNEL_MIX_EDITING !HAS_DUAL_MIXING #if ENABLED(GRADIENT_MIX) @@ -120,7 +120,7 @@ static uint8_t v_index; -#if DUAL_MIXING_EXTRUDER +#if HAS_DUAL_MIXING void _lcd_draw_mix(const uint8_t y) { char tmp[20]; // "100%_100%" sprintf_P(tmp, PSTR("%3d%% %3d%%"), int(mixer.mix[0]), int(mixer.mix[1])); @@ -131,9 +131,7 @@ static uint8_t v_index; void _lcd_mixer_select_vtool() { mixer.T(v_index); - #if DUAL_MIXING_EXTRUDER - _lcd_draw_mix(LCD_HEIGHT - 1); - #endif + TERN_(HAS_DUAL_MIXING, _lcd_draw_mix(LCD_HEIGHT - 1)); } #if CHANNEL_MIX_EDITING @@ -156,7 +154,7 @@ void _lcd_mixer_select_vtool() { void lcd_mixer_mix_edit() { - #if DUAL_MIXING_EXTRUDER && !CHANNEL_MIX_EDITING + #if HAS_DUAL_MIXING && !CHANNEL_MIX_EDITING // Adjust 2-channel mix from the encoder if (ui.encoderPosition != 0) { @@ -194,7 +192,7 @@ void lcd_mixer_mix_edit() { #endif } -#if DUAL_MIXING_EXTRUDER +#if HAS_DUAL_MIXING // // Toggle Dual-Mix @@ -240,12 +238,12 @@ void menu_mixer() { v_index = mixer.get_current_vtool(); EDIT_ITEM(uint8, MSG_ACTIVE_VTOOL, &v_index, 0, MIXING_VIRTUAL_TOOLS - 1, _lcd_mixer_select_vtool - #if DUAL_MIXING_EXTRUDER + #if HAS_DUAL_MIXING , true #endif ); - #if DUAL_MIXING_EXTRUDER + #if HAS_DUAL_MIXING { char tmp[10]; SUBMENU(MSG_MIX, lcd_mixer_mix_edit); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index b7f57c8146..4c16b68b47 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -86,28 +86,16 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { #if HAS_SOFTWARE_ENDSTOPS if (soft_endstops_enabled) switch (axis) { case X_AXIS: - #if ENABLED(MIN_SOFTWARE_ENDSTOP_X) - min = soft_endstop.min.x; - #endif - #if ENABLED(MAX_SOFTWARE_ENDSTOP_X) - max = soft_endstop.max.x; - #endif + TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x); + TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x); break; case Y_AXIS: - #if ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - min = soft_endstop.min.y; - #endif - #if ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - max = soft_endstop.max.y; - #endif + TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y); break; case Z_AXIS: - #if ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - min = soft_endstop.min.z; - #endif - #if ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - max = soft_endstop.max.z; - #endif + TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z); default: break; } #endif // HAS_SOFTWARE_ENDSTOPS @@ -230,9 +218,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int case Y_AXIS: STATIC_ITEM(MSG_MOVE_Y, SS_CENTER|SS_INVERT); break; case Z_AXIS: STATIC_ITEM(MSG_MOVE_Z, SS_CENTER|SS_INVERT); break; default: - #if ENABLED(MANUAL_E_MOVES_RELATIVE) - manual_move_e_origin = current_position.e; - #endif + TERN_(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin = current_position.e); STATIC_ITEM(MSG_MOVE_E, SS_CENTER|SS_INVERT); break; } @@ -275,20 +261,12 @@ void menu_move() { EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstops_enabled); #endif - if ( + if (true #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) - all_axes_homed() - #else - true + && all_axes_homed() #endif ) { - if ( - #if ENABLED(DELTA) - current_position.z <= delta_clip_start_height - #else - true - #endif - ) { + if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) { SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); }); SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); } diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 5229093fd6..921fa91668 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -113,9 +113,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #endif LOOP_S_L_N(n, 1, HOTENDS) PREHEAT_ITEMS(1,n); ACTION_ITEM(MSG_PREHEAT_1_ALL, []() { - #if HAS_HEATED_BED - _preheat_bed(0); - #endif + TERN_(HAS_HEATED_BED, _preheat_bed(0)); HOTEND_LOOP() thermalManager.setTargetHotend(ui.preheat_hotend_temp[0], e); }); #endif // HAS_MULTI_HOTEND @@ -141,9 +139,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #endif LOOP_S_L_N(n, 1, HOTENDS) PREHEAT_ITEMS(2,n); ACTION_ITEM(MSG_PREHEAT_2_ALL, []() { - #if HAS_HEATED_BED - _preheat_bed(1); - #endif + TERN_(HAS_HEATED_BED, _preheat_bed(1)); HOTEND_LOOP() thermalManager.setTargetHotend(ui.preheat_hotend_temp[1], e); }); #endif // HAS_MULTI_HOTEND @@ -284,9 +280,7 @@ void menu_temperature() { // bool has_heat = false; HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } - #if HAS_HEATED_BED - if (thermalManager.temp_bed.target) has_heat = true; - #endif + if (TERN0(HAS_HEATED_BED, thermalManager.temp_bed.target)) has_heat = true; if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); #endif // HAS_TEMP_HOTEND diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index a36f6afc90..2f4c751775 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -67,18 +67,10 @@ const float spm = planner.steps_to_mm[axis]; MenuEditItemBase::draw_edit_screen(msg, BABYSTEP_TO_STR(spm * babystep.accum)); #if ENABLED(BABYSTEP_DISPLAY_TOTAL) - const bool in_view = (true - #if HAS_GRAPHICAL_LCD - && PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1) - #endif - ); + const bool in_view = TERN1(HAS_GRAPHICAL_LCD, PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)); if (in_view) { - #if HAS_GRAPHICAL_LCD - ui.set_font(FONT_MENU); - lcd_moveto(0, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT); - #else - lcd_moveto(0, LCD_HEIGHT - 1); - #endif + TERN_(HAS_GRAPHICAL_LCD, ui.set_font(FONT_MENU)); + lcd_moveto(0, TERN(HAS_GRAPHICAL_LCD, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); lcd_put_wchar(':'); lcd_put_u8str(BABYSTEP_TO_STR(spm * babystep.axis_total[BS_TOTAL_IND(axis)])); diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index a4db6da377..9ad0ac335f 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -68,9 +68,7 @@ static void _lcd_mesh_fine_tune(PGM_P const msg) { if (ui.should_draw()) { MenuEditItemBase::draw_edit_screen(msg, ftostr43sign(mesh_edit_value)); - #if ENABLED(MESH_EDIT_GFX_OVERLAY) - _lcd_zoffset_overlay_gfx(mesh_edit_value); - #endif + TERN_(MESH_EDIT_GFX_OVERLAY, _lcd_zoffset_overlay_gfx(mesh_edit_value)); } } diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 980c561a7e..b427deba73 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -348,9 +348,7 @@ void MarlinUI::init() { update_buttons(); - #if HAS_ENCODER_ACTION - encoderDiff = 0; - #endif + TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); } bool MarlinUI::get_blink() { @@ -487,9 +485,7 @@ bool MarlinUI::get_blink() { void MarlinUI::status_screen() { - #if HAS_LCD_MENU - ENCODER_RATE_MULTIPLY(false); - #endif + TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); #if ENABLED(LCD_PROGRESS_BAR) @@ -590,9 +586,7 @@ void MarlinUI::status_screen() { void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { init(); status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); - #if HAS_LCD_MENU - return_to_status(); - #endif + TERN_(HAS_LCD_MENU, return_to_status()); // RED ALERT. RED ALERT. #ifdef LED_BACKLIGHT_TIMEOUT @@ -608,9 +602,7 @@ void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { - #if HAS_LCD_MENU - refresh(); - #endif + TERN_(HAS_LCD_MENU, refresh()); #if HAS_ENCODER_ACTION if (clear_buttons) buttons = 0; @@ -777,16 +769,12 @@ void MarlinUI::update() { if (ELAPSED(ms, next_button_update_ms)) { encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * (ENCODER_PULSES_PER_STEP) * encoderDirection; if (touch_buttons & EN_A) encoderDiff *= -1; - #if ENABLED(AUTO_BED_LEVELING_UBL) - if (external_control) ubl.encoder_diff = encoderDiff; - #endif + TERN_(AUTO_BED_LEVELING_UBL, if (external_control) ubl.encoder_diff = encoderDiff); next_button_update_ms = ms + repeat_delay; // Assume the repeat delay if (!wait_for_unclick) { next_button_update_ms += 250; // Longer delay on first press wait_for_unclick = true; // Avoid Back/Select click while repeating - #if HAS_BUZZER - buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ); - #endif + TERN_(HAS_BUZZER, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); } } } @@ -813,11 +801,7 @@ void MarlinUI::update() { #endif // HAS_LCD_MENU - if (ELAPSED(ms, next_lcd_update_ms) - #if HAS_GRAPHICAL_LCD - || drawing_screen - #endif - ) { + if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_GRAPHICAL_LCD, drawing_screen)) { next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; @@ -825,25 +809,18 @@ void MarlinUI::update() { if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; - #if HAS_ENCODER_ACTION - touch_buttons = touch.read_buttons(); - #endif + TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); #endif - #if ENABLED(LCD_HAS_STATUS_INDICATORS) - update_indicators(); - #endif + TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); #if HAS_ENCODER_ACTION - #if HAS_SLOW_BUTTONS - slow_buttons = read_slow_buttons(); // Buttons that take too long to read in interrupt context - #endif + TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context - #if ENABLED(REPRAPWORLD_KEYPAD) - if (handle_keypad()) RESET_STATUS_TIMEOUT(); - #endif + if (TERN0(REPRAPWORLD_KEYPAD, handle_keypad())) + RESET_STATUS_TIMEOUT(); const float abs_diff = ABS(encoderDiff); const bool encoderPastThreshold = (abs_diff >= (ENCODER_PULSES_PER_STEP)); @@ -943,9 +920,7 @@ void MarlinUI::update() { break; } // switch - #if HAS_ADC_BUTTONS - keypad_buttons = 0; - #endif + TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); #if HAS_GRAPHICAL_LCD @@ -984,9 +959,7 @@ void MarlinUI::update() { #endif - #if HAS_LCD_MENU - lcd_clicked = false; - #endif + TERN_(HAS_LCD_MENU, lcd_clicked = false); // Keeping track of the longest time for an individual LCD update. // Used to do screen throttling when the planner starts to fill up. @@ -1229,9 +1202,7 @@ void MarlinUI::update() { case encrot3: ENCODER_SPIN(encrot2, encrot0); break; } if (external_control) { - #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.encoder_diff = encoderDiff; // Make encoder rotation available to UBL G29 mesh editing. - #endif + TERN_(AUTO_BED_LEVELING_UBL, ubl.encoder_diff = encoderDiff); // Make encoder rotation available to UBL G29 mesh editing. encoderDiff = 0; // Hide the encoder event from the current screen handler. } lastEncoderBits = enc; @@ -1294,9 +1265,7 @@ void MarlinUI::update() { status_scroll_offset = 0; #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onStatusChanged(status_message); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); } bool MarlinUI::has_status() { return (status_message[0] != '\0'); } @@ -1304,9 +1273,7 @@ void MarlinUI::update() { void MarlinUI::set_status(const char * const message, const bool persist) { if (alert_level) return; - #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_notify(message); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_action_notify(message)); // Here we have a problem. The message is encoded in UTF8, so // arbitrarily cutting it will be a problem. We MUST be sure @@ -1347,9 +1314,7 @@ void MarlinUI::update() { if (level < alert_level) return; alert_level = level; - #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_notify(message); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_action_notify(message)); // Since the message is encoded in UTF8 it must // only be cut on a character boundary. @@ -1374,9 +1339,7 @@ void MarlinUI::update() { void MarlinUI::set_alert_status_P(PGM_P const message) { set_status_P(message, 1); - #if HAS_LCD_MENU - return_to_status(); - #endif + TERN_(HAS_LCD_MENU, return_to_status()); } PGM_P print_paused = GET_TEXT(MSG_PRINT_PAUSED); @@ -1436,14 +1399,10 @@ void MarlinUI::update() { #ifdef ACTION_ON_CANCEL host_action_cancel(); #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR)); print_job_timer.stop(); set_status_P(GET_TEXT(MSG_PRINT_ABORTED)); - #if HAS_LCD_MENU - return_to_status(); - #endif + TERN_(HAS_LCD_MENU, return_to_status()); } #if ANY(PARK_HEAD_ON_PAUSE, SDSUPPORT) @@ -1456,16 +1415,12 @@ void MarlinUI::update() { defer_status_screen(); #endif - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); set_status_P(print_paused); #if ENABLED(PARK_HEAD_ON_PAUSE) - #if HAS_SPI_LCD - lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress - #endif + TERN_(HAS_SPI_LCD, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); // Show message immediately to let user know about pause in progress queue.inject_P(PSTR("M25 P\nM24")); #elif ENABLED(SDSUPPORT) queue.inject_P(PSTR("M25")); @@ -1476,9 +1431,7 @@ void MarlinUI::update() { void MarlinUI::resume_print() { reset_status(); - #if ENABLED(PARK_HEAD_ON_PAUSE) - wait_for_heatup = wait_for_user = false; - #endif + TERN_(PARK_HEAD_ON_PAUSE, wait_for_heatup = wait_for_user = false); if (IS_SD_PAUSED()) queue.inject_P(M24_STR); #ifdef ACTION_ON_RESUME host_action_resume(); @@ -1543,30 +1496,22 @@ void MarlinUI::update() { void MarlinUI::media_changed(const uint8_t old_status, const uint8_t status) { if (old_status == status) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaError(); // Failed to mount/unmount - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMediaError()); // Failed to mount/unmount return; } if (status) { if (old_status < 2) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaInserted(); // ExtUI response - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMediaInserted()); // ExtUI response set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); } } else { if (old_status < 2) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaRemoved(); // ExtUI response - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onMediaRemoved()); // ExtUI response #if PIN_EXISTS(SD_DETECT) set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); - #if HAS_LCD_MENU - return_to_status(); - #endif + TERN_(HAS_LCD_MENU, return_to_status()); #endif } } @@ -1581,9 +1526,7 @@ void MarlinUI::update() { const millis_t ms = millis(); #endif - #if HAS_SPI_LCD - next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; // Delay LCD update for SD activity - #endif + TERN_(HAS_SPI_LCD, next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL); // Delay LCD update for SD activity #ifdef LED_BACKLIGHT_TIMEOUT leds.reset_timeout(ms); diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 0c7c03372f..5a4805edf7 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -41,7 +41,9 @@ #endif // I2C buttons must be read in the main thread -#define HAS_SLOW_BUTTONS EITHER(LCD_I2C_VIKI, LCD_I2C_PANELOLU2) +#if EITHER(LCD_I2C_VIKI, LCD_I2C_PANELOLU2) + #define HAS_SLOW_BUTTONS 1 +#endif #if HAS_SPI_LCD @@ -64,11 +66,7 @@ uint8_t get_ADC_keyValue(); #endif - #if ENABLED(TOUCH_BUTTONS) - #define LCD_UPDATE_INTERVAL 50 - #else - #define LCD_UPDATE_INTERVAL 100 - #endif + #define LCD_UPDATE_INTERVAL TERN(TOUCH_BUTTONS, 50, 100) #if HAS_LCD_MENU @@ -207,12 +205,12 @@ #define BL_DW 4 // Down #define BL_RI 3 // Right #define BL_ST 2 // Red Button - #define B_LE (_BV(BL_LE)) - #define B_UP (_BV(BL_UP)) - #define B_MI (_BV(BL_MI)) - #define B_DW (_BV(BL_DW)) - #define B_RI (_BV(BL_RI)) - #define B_ST (_BV(BL_ST)) + #define B_LE _BV(BL_LE) + #define B_UP _BV(BL_UP) + #define B_MI _BV(BL_MI) + #define B_DW _BV(BL_DW) + #define B_RI _BV(BL_RI) + #define B_ST _BV(BL_ST) #ifndef BUTTON_CLICK #define BUTTON_CLICK() (buttons & (B_MI|B_ST)) @@ -258,9 +256,7 @@ class MarlinUI { public: MarlinUI() { - #if HAS_LCD_MENU - currentScreen = status_screen; - #endif + TERN_(HAS_LCD_MENU, currentScreen = status_screen); } #if HAS_BUZZER @@ -530,9 +526,7 @@ public: #if ENABLED(G26_MESH_VALIDATION) FORCE_INLINE static void chirp() { - #if HAS_BUZZER - buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ); - #endif + TERN_(HAS_BUZZER, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); } #endif @@ -605,15 +599,11 @@ public: } FORCE_INLINE static void encoder_direction_menus() { - #if ENABLED(REVERSE_MENU_DIRECTION) - encoderDirection = -(ENCODERBASE); - #endif + TERN_(REVERSE_MENU_DIRECTION, encoderDirection = -(ENCODERBASE)); } FORCE_INLINE static void encoder_direction_select() { - #if ENABLED(REVERSE_SELECT_DIRECTION) - encoderDirection = -(ENCODERBASE); - #endif + TERN_(REVERSE_SELECT_DIRECTION, encoderDirection = -(ENCODERBASE)); } #else diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index ad70537141..a664936adb 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -923,9 +923,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* monitor_update(E5); #endif - #if ENABLED(L6470_DEBUG) - if (report_L6470_status) DEBUG_EOL(); - #endif + if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL(); spi_active = false; // done with all SPI transfers - clear handshake flags spi_abort = false; diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index ecbfeb331e..c691a7db3b 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -42,9 +42,7 @@ Nozzle nozzle; * @param strokes number of strokes to execute */ void Nozzle::stroke(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes) { - #if ENABLED(NOZZLE_CLEAN_GOBACK) - const xyz_pos_t oldpos = current_position; - #endif + TERN_(NOZZLE_CLEAN_GOBACK, const xyz_pos_t oldpos = current_position); // Move to the starting point #if ENABLED(NOZZLE_CLEAN_NO_Z) @@ -59,9 +57,7 @@ Nozzle nozzle; do_blocking_move_to_xy(start); } - #if ENABLED(NOZZLE_CLEAN_GOBACK) - do_blocking_move_to(oldpos); - #endif + TERN_(NOZZLE_CLEAN_GOBACK, do_blocking_move_to(oldpos)); } /** @@ -77,9 +73,7 @@ Nozzle nozzle; const xy_pos_t diff = end - start; if (!diff.x || !diff.y) return; - #if ENABLED(NOZZLE_CLEAN_GOBACK) - const xyz_pos_t back = current_position; - #endif + TERN_(NOZZLE_CLEAN_GOBACK, const xyz_pos_t back = current_position); #if ENABLED(NOZZLE_CLEAN_NO_Z) do_blocking_move_to_xy(start); @@ -108,9 +102,7 @@ Nozzle nozzle; } } - #if ENABLED(NOZZLE_CLEAN_GOBACK) - do_blocking_move_to(back); - #endif + TERN_(NOZZLE_CLEAN_GOBACK, do_blocking_move_to(back)); } /** @@ -124,15 +116,8 @@ Nozzle nozzle; void Nozzle::circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const float &radius) { if (strokes == 0) return; - #if ENABLED(NOZZLE_CLEAN_GOBACK) - const xyz_pos_t back = current_position; - #endif - - #if ENABLED(NOZZLE_CLEAN_NO_Z) - do_blocking_move_to_xy(start); - #else - do_blocking_move_to(start); - #endif + TERN_(NOZZLE_CLEAN_GOBACK, const xyz_pos_t back = current_position); + TERN(NOZZLE_CLEAN_NO_Z, do_blocking_move_to_xy, do_blocking_move_to)(start); LOOP_L_N(s, strokes) LOOP_L_N(i, NOZZLE_CLEAN_CIRCLE_FN) @@ -144,9 +129,7 @@ Nozzle nozzle; // Let's be safe do_blocking_move_to_xy(start); - #if ENABLED(NOZZLE_CLEAN_GOBACK) - do_blocking_move_to(back); - #endif + TERN_(NOZZLE_CLEAN_GOBACK, do_blocking_move_to(back)); } /** diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index c75eb2da09..13706a5b8e 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -34,14 +34,10 @@ millis_t Stopwatch::startTimestamp; millis_t Stopwatch::stopTimestamp; bool Stopwatch::stop() { - #if ENABLED(DEBUG_STOPWATCH) - Stopwatch::debug(PSTR("stop")); - #endif + Stopwatch::debug(PSTR("stop")); if (isRunning() || isPaused()) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPrintTimerStopped(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerStopped()); state = STOPPED; stopTimestamp = millis(); return true; @@ -50,14 +46,10 @@ bool Stopwatch::stop() { } bool Stopwatch::pause() { - #if ENABLED(DEBUG_STOPWATCH) - Stopwatch::debug(PSTR("pause")); - #endif + Stopwatch::debug(PSTR("pause")); if (isRunning()) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPrintTimerPaused(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerPaused()); state = PAUSED; stopTimestamp = millis(); return true; @@ -66,13 +58,9 @@ bool Stopwatch::pause() { } bool Stopwatch::start() { - #if ENABLED(DEBUG_STOPWATCH) - Stopwatch::debug(PSTR("start")); - #endif + Stopwatch::debug(PSTR("start")); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPrintTimerStarted(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerStarted()); if (!isRunning()) { if (isPaused()) accumulator = duration(); @@ -86,18 +74,14 @@ bool Stopwatch::start() { } void Stopwatch::resume(const millis_t with_time) { - #if ENABLED(DEBUG_STOPWATCH) - Stopwatch::debug(PSTR("resume")); - #endif + Stopwatch::debug(PSTR("resume")); reset(); if ((accumulator = with_time)) state = RUNNING; } void Stopwatch::reset() { - #if ENABLED(DEBUG_STOPWATCH) - Stopwatch::debug(PSTR("reset")); - #endif + Stopwatch::debug(PSTR("reset")); state = STOPPED; startTimestamp = 0; diff --git a/Marlin/src/libs/stopwatch.h b/Marlin/src/libs/stopwatch.h index 4aac815c8d..24ba601963 100644 --- a/Marlin/src/libs/stopwatch.h +++ b/Marlin/src/libs/stopwatch.h @@ -114,5 +114,9 @@ class Stopwatch { */ static void debug(const char func[]); + #else + + static inline void debug(const char[]) {} + #endif }; diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index d201a45e6d..698447a4be 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -126,9 +126,9 @@ void M710_report(const bool forReplay); #endif -#define HAS_CASE_LIGHT_BRIGHTNESS (ENABLED(CASE_LIGHT_MENU) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS)) -#if HAS_CASE_LIGHT_BRIGHTNESS +#if ENABLED(CASE_LIGHT_MENU) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS) #include "../feature/caselight.h" + #define HAS_CASE_LIGHT_BRIGHTNESS 1 #endif #pragma pack(push, 1) // No padding between variables @@ -235,7 +235,7 @@ typedef struct SettingsDataStruct { #if ENABLED(USE_TEMP_EXT_COMPENSATION) , z_offsets_ext[COUNT(temp_comp.z_offsets_ext)] // M871 E I V #endif - ; + ; #endif // @@ -411,13 +411,9 @@ void MarlinSettings::postprocess() { // Make sure delta kinematics are updated before refreshing the // planner position so the stepper counts will be set correctly. - #if ENABLED(DELTA) - recalc_delta_settings(); - #endif + TERN_(DELTA, recalc_delta_settings()); - #if ENABLED(PIDTEMP) - thermalManager.updatePID(); - #endif + TERN_(PIDTEMP, thermalManager.updatePID()); #if DISABLED(NO_VOLUMETRICS) planner.calculate_volumetric_multipliers(); @@ -432,29 +428,17 @@ void MarlinSettings::postprocess() { update_software_endstops((AxisEnum)i); } - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - set_z_fade_height(new_z_fade_height, false); // false = no report - #endif + TERN_(ENABLE_LEVELING_FADE_HEIGHT, set_z_fade_height(new_z_fade_height, false)); // false = no report - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - refresh_bed_level(); - #endif + TERN_(AUTO_BED_LEVELING_BILINEAR, refresh_bed_level()); - #if HAS_MOTOR_CURRENT_PWM - stepper.refresh_motor_power(); - #endif + TERN_(HAS_MOTOR_CURRENT_PWM, stepper.refresh_motor_power()); - #if ENABLED(FWRETRACT) - fwretract.refresh_autoretract(); - #endif + TERN_(FWRETRACT, fwretract.refresh_autoretract()); - #if HAS_LINEAR_E_JERK - planner.recalculate_max_e_jerk(); - #endif + TERN_(HAS_LINEAR_E_JERK, planner.recalculate_max_e_jerk()); - #if HAS_CASE_LIGHT_BRIGHTNESS - update_case_light(); - #endif + TERN_(HAS_CASE_LIGHT_BRIGHTNESS, update_case_light()); // Refresh steps_to_mm with the reciprocal of axis_steps_per_mm // and init stepper.count[], planner.position[] with current_position @@ -585,9 +569,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(planner_max_jerk); #endif - #if ENABLED(CLASSIC_JERK) - dummyf = 0.02f; - #endif + TERN_(CLASSIC_JERK, dummyf = 0.02f); EEPROM_WRITE(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm)); } @@ -1130,18 +1112,10 @@ void MarlinSettings::postprocess() { { tmc_sgt_t tmc_sgt{0}; #if USE_SENSORLESS - #if X_SENSORLESS - tmc_sgt.X = stepperX.homing_threshold(); - #endif - #if X2_SENSORLESS - tmc_sgt.X2 = stepperX2.homing_threshold(); - #endif - #if Y_SENSORLESS - tmc_sgt.Y = stepperY.homing_threshold(); - #endif - #if Z_SENSORLESS - tmc_sgt.Z = stepperZ.homing_threshold(); - #endif + TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()); + TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold()); + TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()); + TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()); #endif EEPROM_WRITE(tmc_sgt); } @@ -1362,9 +1336,7 @@ void MarlinSettings::postprocess() { if (!eeprom_error) LCD_MESSAGEPGM(MSG_SETTINGS_STORED); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onConfigurationStoreWritten(!eeprom_error); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onConfigurationStoreWritten(!eeprom_error)); return !eeprom_error; } @@ -1703,12 +1675,8 @@ void MarlinSettings::postprocess() { PID_PARAM(Kp, e) = pidcf.Kp; PID_PARAM(Ki, e) = scalePID_i(pidcf.Ki); PID_PARAM(Kd, e) = scalePID_d(pidcf.Kd); - #if ENABLED(PID_EXTRUSION_SCALING) - PID_PARAM(Kc, e) = pidcf.Kc; - #endif - #if ENABLED(PID_FAN_SCALING) - PID_PARAM(Kf, e) = pidcf.Kf; - #endif + TERN_(PID_EXTRUSION_SCALING, PID_PARAM(Kc, e) = pidcf.Kc); + TERN_(PID_FAN_SCALING, PID_PARAM(Kf, e) = pidcf.Kf); } #endif } @@ -1761,9 +1729,7 @@ void MarlinSettings::postprocess() { int16_t lcd_contrast; EEPROM_READ(lcd_contrast); - #if HAS_LCD_CONTRAST - ui.set_contrast(lcd_contrast); - #endif + TERN_(HAS_LCD_CONTRAST, ui.set_contrast(lcd_contrast)); } // @@ -1981,9 +1947,7 @@ void MarlinSettings::postprocess() { stepperX2.homing_threshold(tmc_sgt.X); #endif #endif - #if X2_SENSORLESS - stepperX2.homing_threshold(tmc_sgt.X2); - #endif + TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2)); #ifdef Y_STALL_SENSITIVITY #if AXIS_HAS_STALLGUARD(Y) stepperY.homing_threshold(tmc_sgt.Y); @@ -2284,9 +2248,7 @@ void MarlinSettings::postprocess() { bool MarlinSettings::load() { if (validate()) { const bool success = _load(); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onConfigurationStoreRead(success); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onConfigurationStoreRead(success)); return success; } reset(); @@ -2428,9 +2390,7 @@ void MarlinSettings::reset() { #define DEFAULT_ZJERK 0 #endif planner.max_jerk.set(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK); - #if HAS_CLASSIC_E_JERK - planner.max_jerk.e = DEFAULT_EJERK; - #endif + TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;); #endif #if DISABLED(CLASSIC_JERK) @@ -2443,9 +2403,7 @@ void MarlinSettings::reset() { home_offset.reset(); #endif - #if HAS_HOTEND_OFFSET - reset_hotend_offsets(); - #endif + TERN_(HAS_HOTEND_OFFSET, reset_hotend_offsets()); // // Filament Runout Sensor @@ -2486,37 +2444,23 @@ void MarlinSettings::reset() { #endif #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onFactoryReset(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); // // Case Light Brightness // - - #if HAS_CASE_LIGHT_BRIGHTNESS - case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS; - #endif + TERN_(HAS_CASE_LIGHT_BRIGHTNESS, case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS); // // Magnetic Parking Extruder // - - #if ENABLED(MAGNETIC_PARKING_EXTRUDER) - mpe_settings_init(); - #endif + TERN_(MAGNETIC_PARKING_EXTRUDER, mpe_settings_init()); // // Global Leveling // - - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - new_z_fade_height = 0.0; - #endif - - #if HAS_LEVELING - reset_bed_level(); - #endif + TERN_(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height = 0.0); + TERN_(HAS_LEVELING, reset_bed_level()); #if HAS_BED_PROBE constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET; @@ -2532,18 +2476,12 @@ void MarlinSettings::reset() { // // Z Stepper Auto-alignment points // - - #if ENABLED(Z_STEPPER_AUTO_ALIGN) - z_stepper_align.reset_to_default(); - #endif + TERN_(Z_STEPPER_AUTO_ALIGN, z_stepper_align.reset_to_default()); // // Servo Angles // - - #if ENABLED(EDITABLE_SERVO_ANGLES) - COPY(servo_angles, base_servo_angles); // When not editable only one copy of servo angles exists - #endif + TERN_(EDITABLE_SERVO_ANGLES, COPY(servo_angles, base_servo_angles)); // When not editable only one copy of servo angles exists // // BLTOUCH @@ -2564,7 +2502,6 @@ void MarlinSettings::reset() { delta_diagonal_rod = DELTA_DIAGONAL_ROD; delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; delta_tower_angle_trim = dta; - #endif #if ENABLED(X_DUAL_ENDSTOPS) @@ -2622,23 +2559,15 @@ void MarlinSettings::reset() { PID_PARAM(Kp, e) = float(DEFAULT_Kp); PID_PARAM(Ki, e) = scalePID_i(DEFAULT_Ki); PID_PARAM(Kd, e) = scalePID_d(DEFAULT_Kd); - #if ENABLED(PID_EXTRUSION_SCALING) - PID_PARAM(Kc, e) = DEFAULT_Kc; - #endif - - #if ENABLED(PID_FAN_SCALING) - PID_PARAM(Kf, e) = DEFAULT_Kf; - #endif + TERN_(PID_EXTRUSION_SCALING, PID_PARAM(Kc, e) = DEFAULT_Kc); + TERN_(PID_FAN_SCALING, PID_PARAM(Kf, e) = DEFAULT_Kf); } #endif // // PID Extrusion Scaling // - - #if ENABLED(PID_EXTRUSION_SCALING) - thermalManager.lpq_len = 20; // Default last-position-queue size - #endif + TERN_(PID_EXTRUSION_SCALING, thermalManager.lpq_len = 20); // Default last-position-queue size // // Heated Bed PID @@ -2653,67 +2582,39 @@ void MarlinSettings::reset() { // // User-Defined Thermistors // - - #if HAS_USER_THERMISTORS - thermalManager.reset_user_thermistors(); - #endif + TERN_(HAS_USER_THERMISTORS, thermalManager.reset_user_thermistors()); // // LCD Contrast // - - #if HAS_LCD_CONTRAST - ui.set_contrast(DEFAULT_LCD_CONTRAST); - #endif + TERN_(HAS_LCD_CONTRAST, ui.set_contrast(DEFAULT_LCD_CONTRAST)); // // Controller Fan // - #if ENABLED(USE_CONTROLLER_FAN) - controllerFan.reset(); - #endif + TERN_(USE_CONTROLLER_FAN, controllerFan.reset()); // // Power-Loss Recovery // - - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.enable(ENABLED(PLR_ENABLED_DEFAULT)); - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.enable(ENABLED(PLR_ENABLED_DEFAULT))); // // Firmware Retraction // - - #if ENABLED(FWRETRACT) - fwretract.reset(); - #endif + TERN_(FWRETRACT, fwretract.reset()); // // Volumetric & Filament Size // #if DISABLED(NO_VOLUMETRICS) - - parser.volumetric_enabled = - #if ENABLED(VOLUMETRIC_DEFAULT_ON) - true - #else - false - #endif - ; + parser.volumetric_enabled = ENABLED(VOLUMETRIC_DEFAULT_ON); LOOP_L_N(q, COUNT(planner.filament_size)) planner.filament_size[q] = DEFAULT_NOMINAL_FILAMENT_DIA; - #endif - endstops.enable_globally( - #if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) - true - #else - false - #endif - ); + endstops.enable_globally(ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)); reset_stepper_drivers(); @@ -2724,9 +2625,7 @@ void MarlinSettings::reset() { #if ENABLED(LIN_ADVANCE) LOOP_L_N(i, EXTRUDERS) { planner.extruder_advance_K[i] = LIN_ADVANCE_K; - #if ENABLED(EXTRA_LIN_ADVANCE_K) - other_extruder_advance_K[i] = LIN_ADVANCE_K; - #endif + TERN_(EXTRA_LIN_ADVANCE_K, other_extruder_advance_K[i] = LIN_ADVANCE_K); } #endif @@ -2743,15 +2642,11 @@ void MarlinSettings::reset() { // // CNC Coordinate System // - - #if ENABLED(CNC_COORDINATE_SYSTEMS) - (void)gcode.select_coordinate_system(-1); // Go back to machine space - #endif + TERN_(CNC_COORDINATE_SYSTEMS, (void)gcode.select_coordinate_system(-1)); // Go back to machine space // // Skew Correction // - #if ENABLED(SKEW_CORRECTION_GCODE) planner.skew_factor.xy = XY_SKEW_FACTOR; #if ENABLED(SKEW_CORRECTION_FOR_Z) @@ -2763,7 +2658,6 @@ void MarlinSettings::reset() { // // Advanced Pause filament load & unload lengths // - #if ENABLED(ADVANCED_PAUSE_FEATURE) LOOP_L_N(e, EXTRUDERS) { fc_settings[e].unload_length = FILAMENT_CHANGE_UNLOAD_LENGTH; @@ -2776,9 +2670,7 @@ void MarlinSettings::reset() { DEBUG_ECHO_START(); DEBUG_ECHOLNPGM("Hardcoded Default Settings Loaded"); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onFactoryReset(); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); } #if DISABLED(DISABLE_M503) @@ -2959,9 +2851,7 @@ void MarlinSettings::reset() { #endif #if HAS_CLASSIC_JERK " X Y Z" - #if HAS_CLASSIC_E_JERK - " E" - #endif + TERN_(HAS_CLASSIC_E_JERK, " E") #endif ); CONFIG_ECHO_START(); @@ -3237,9 +3127,7 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" M250 C", ui.contrast); #endif - #if ENABLED(CONTROLLER_FAN_EDITABLE) - M710_report(forReplay); - #endif + TERN_(CONTROLLER_FAN_EDITABLE, M710_report(forReplay)); #if ENABLED(POWER_LOSS_RECOVERY) CONFIG_ECHO_HEADING("Power-Loss Recovery:"); diff --git a/Marlin/src/module/configuration_store.h b/Marlin/src/module/configuration_store.h index f2e84c9664..e96fe5909b 100644 --- a/Marlin/src/module/configuration_store.h +++ b/Marlin/src/module/configuration_store.h @@ -38,9 +38,7 @@ class MarlinSettings { reset(); #if ENABLED(EEPROM_SETTINGS) const bool success = save(); - #if ENABLED(EEPROM_CHITCHAT) - if (success) report(); - #endif + if (TERN0(EEPROM_CHITCHAT, success)) report(); return success; #else return true; diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 1f532767cc..a91a8e8545 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -249,11 +249,7 @@ void home_delta() { #endif // Move all carriages together linearly until an endstop is hit. - current_position.z = (delta_height + 10 - #if HAS_BED_PROBE - - probe.offset.z - #endif - ); + current_position.z = (delta_height + 10 - TERN0(HAS_BED_PROBE, probe.offset.z)); line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index f55d56b959..092043b59c 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -276,27 +276,17 @@ void Endstops::init() { #endif #endif - #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) - setup_endstop_interrupts(); - #endif + TERN_(ENDSTOP_INTERRUPTS_FEATURE, setup_endstop_interrupts()); // Enable endstops - enable_globally( - #if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) - true - #else - false - #endif - ); + enable_globally(ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)); } // Endstops::init // Called at ~1KHz from Temperature ISR: Poll endstop state if required void Endstops::poll() { - #if ENABLED(PINS_DEBUGGING) - run_monitor(); // report changes in endstop status - #endif + TERN_(PINS_DEBUGGING, run_monitor()); // Report changes in endstop status #if DISABLED(ENDSTOP_INTERRUPTS_FEATURE) update(); @@ -341,14 +331,9 @@ void Endstops::not_homing() { void Endstops::resync() { if (!abort_enabled()) return; // If endstops/probes are disabled the loop below can hang - #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) - update(); - #else - safe_delay(2); // Wait for Temperature ISR to run at least once (runs at 1KHz) - #endif - #if ENDSTOP_NOISE_THRESHOLD - while (endstop_poll_count) safe_delay(1); - #endif + // Wait for Temperature ISR to run at least once (runs at 1KHz) + TERN(ENDSTOP_INTERRUPTS_FEATURE, update(), safe_delay(2)); + while (TERN0(ENDSTOP_NOISE_THRESHOLD, endstop_poll_count)) safe_delay(1); } #if ENABLED(PINS_DEBUGGING) @@ -397,9 +382,7 @@ void Endstops::event_handler() { #endif SERIAL_EOL(); - #if HAS_SPI_LCD - ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP); - #endif + TERN_(HAS_SPI_LCD, ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP)); #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) if (planner.abort_on_endstop_hit) { @@ -420,9 +403,7 @@ static void print_es_state(const bool is_hit, PGM_P const label=nullptr) { } void _O2 Endstops::report_states() { - #if ENABLED(BLTOUCH) - bltouch._set_SW_mode(); - #endif + TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); #define ES_REPORT(S) print_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING, PSTR(STR_##S)) #if HAS_X_MIN @@ -494,13 +475,9 @@ void _O2 Endstops::report_states() { #undef _CASE_RUNOUT #endif #endif - #if ENABLED(BLTOUCH) - bltouch._reset_SW_mode(); - #endif - #if ENABLED(JOYSTICK_DEBUG) - joystick.report(); - #endif + TERN_(BLTOUCH, bltouch._reset_SW_mode()); + TERN_(JOYSTICK_DEBUG, joystick.report()); } // Endstops::report_states @@ -796,12 +773,8 @@ void Endstops::update() { if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_DIR < 0) - if (true - #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - && z_probe_enabled - #elif HAS_CUSTOM_PROBE_PIN - && !z_probe_enabled - #endif + if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) + && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) ) PROCESS_ENDSTOP_Z(MIN); #endif @@ -852,15 +825,9 @@ void Endstops::update() { } void Endstops::clear_endstop_state() { - #if X_SPI_SENSORLESS - CBI(live_state, X_STOP); - #endif - #if Y_SPI_SENSORLESS - CBI(live_state, Y_STOP); - #endif - #if Z_SPI_SENSORLESS - CBI(live_state, Z_STOP); - #endif + TERN_(X_SPI_SENSORLESS, CBI(live_state, X_STOP)); + TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_STOP)); + TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_STOP)); } #endif // SPI_ENDSTOPS diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 71353abb34..0121492bd6 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -42,15 +42,9 @@ class Endstops { public: #if HAS_EXTRA_ENDSTOPS typedef uint16_t esbits_t; - #if ENABLED(X_DUAL_ENDSTOPS) - static float x2_endstop_adj; - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - static float y2_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - static float z2_endstop_adj; - #endif + TERN_(X_DUAL_ENDSTOPS, static float x2_endstop_adj); + TERN_(Y_DUAL_ENDSTOPS, static float y2_endstop_adj); + TERN_(Z_MULTI_ENDSTOPS, static float z2_endstop_adj); #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 static float z3_endstop_adj; #endif @@ -83,11 +77,7 @@ class Endstops { * Are endstops or the probe set to abort the move? */ FORCE_INLINE static bool abort_enabled() { - return (enabled - #if HAS_BED_PROBE - || z_probe_enabled - #endif - ); + return enabled || TERN0(HAS_BED_PROBE, z_probe_enabled); } static inline bool global_enabled() { return enabled_globally; } diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index c2301aa343..94b4316fa5 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -204,9 +204,7 @@ xyz_pos_t cartes; inline void report_more_positions() { stepper.report_positions(); - #if IS_SCARA - scara_report_positions(); - #endif + TERN_(IS_SCARA, scara_report_positions()); } // Report the logical position for a given machine position @@ -329,9 +327,7 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { #if EXTRUDERS void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s) { - #if HAS_FILAMENT_SENSOR - runout.reset(); - #endif + TERN_(HAS_FILAMENT_SENSOR, runout.reset()); current_position.e += length / planner.e_factor[active_extruder]; line_to_current_position(fr_mm_s); planner.synchronize(); @@ -554,7 +550,8 @@ void restore_feedrate_and_scaling() { */ void update_software_endstops(const AxisEnum axis #if HAS_HOTEND_OFFSET - , const uint8_t old_tool_index/*=0*/, const uint8_t new_tool_index/*=0*/ + , const uint8_t old_tool_index/*=0*/ + , const uint8_t new_tool_index/*=0*/ #endif ) { @@ -587,11 +584,7 @@ void restore_feedrate_and_scaling() { #elif ENABLED(DELTA) soft_endstop.min[axis] = base_min_pos(axis); - soft_endstop.max[axis] = (axis == Z_AXIS ? delta_height - #if HAS_BED_PROBE - - probe.offset.z - #endif - : base_max_pos(axis)); + soft_endstop.max[axis] = (axis == Z_AXIS) ? delta_height - TERN0(HAS_BED_PROBE, probe.offset.z) : base_max_pos(axis); switch (axis) { case X_AXIS: @@ -644,9 +637,7 @@ void restore_feedrate_and_scaling() { #if IS_KINEMATIC - #if ENABLED(DELTA) - if (!all_axes_homed()) return; - #endif + if (TERN0(DELTA, !all_axes_homed())) return; #if HAS_HOTEND_OFFSET && ENABLED(DELTA) // The effector center position will be the target minus the hotend offset. @@ -656,11 +647,7 @@ void restore_feedrate_and_scaling() { constexpr xy_pos_t offs{0}; #endif - if (true - #if IS_SCARA - && TEST(axis_homed, X_AXIS) && TEST(axis_homed, Y_AXIS) - #endif - ) { + if (TERN1(IS_SCARA, TEST(axis_homed, X_AXIS) && TEST(axis_homed, Y_AXIS))) { const float dist_2 = HYPOT2(target.x - offs.x, target.y - offs.y); if (dist_2 > delta_max_radius_2) target *= float(delta_max_radius / SQRT(dist_2)); // 200 / 300 = 0.66 @@ -811,8 +798,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif - )) - break; + )) break; } // Ensure last segment arrives at target location. @@ -883,8 +869,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif - )) - break; + )) break; } // Since segment_distance is only approximate, @@ -1090,9 +1075,7 @@ void prepare_line_to_destination() { #endif // PREVENT_COLD_EXTRUSION || PREVENT_LENGTHY_EXTRUDE - #if ENABLED(DUAL_X_CARRIAGE) - if (dual_x_carriage_unpark()) return; - #endif + if (TERN0(DUAL_X_CARRIAGE, dual_x_carriage_unpark())) return; if ( #if UBL_SEGMENTED @@ -1135,9 +1118,7 @@ bool axis_unhomed_error(uint8_t axis_bits/*=0x07*/) { ); SERIAL_ECHO_START(); SERIAL_ECHOLN(msg); - #if HAS_DISPLAY - ui.set_status(msg); - #endif + TERN_(HAS_DISPLAY, ui.set_status(msg)); return true; } return false; @@ -1147,9 +1128,8 @@ bool axis_unhomed_error(uint8_t axis_bits/*=0x07*/) { * Homing bump feedrate (mm/s) */ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { - #if HOMING_Z_WITH_PROBE - if (axis == Z_AXIS) return MMM_TO_MMS(Z_PROBE_SPEED_SLOW); - #endif + if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS)) + return MMM_TO_MMS(Z_PROBE_SPEED_SLOW); static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); if (hbd < 1) { @@ -1224,9 +1204,7 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { } #endif - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - sg_guard_period = millis() + default_sg_guard_duration; - #endif + TERN_(IMPROVE_HOMING_RELIABILITY, sg_guard_period = millis() + default_sg_guard_duration); return stealth_states; } @@ -1316,11 +1294,8 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t #endif // Only do some things when moving towards an endstop - const int8_t axis_home_dir = - #if ENABLED(DUAL_X_CARRIAGE) - (axis == X_AXIS) ? x_home_dir(active_extruder) : - #endif - home_dir(axis); + const int8_t axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) + ? x_home_dir(active_extruder) : home_dir(axis); const bool is_home_dir = (axis_home_dir > 0) == (distance > 0); #if ENABLED(SENSORLESS_HOMING) @@ -1334,9 +1309,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t #endif // Disable stealthChop if used. Enable diag1 pin on driver. - #if ENABLED(SENSORLESS_HOMING) - stealth_states = start_sensorless_homing_per_axis(axis); - #endif + TERN_(SENSORLESS_HOMING, stealth_states = start_sensorless_homing_per_axis(axis)); } #if IS_SCARA @@ -1375,9 +1348,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t endstops.validate_homing_move(); // Re-enable stealthChop if used. Disable diag1 pin on driver. - #if ENABLED(SENSORLESS_HOMING) - end_sensorless_homing_per_axis(axis, stealth_states); - #endif + TERN_(SENSORLESS_HOMING, end_sensorless_homing_per_axis(axis, stealth_states)); } if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< do_homing_move(", axis_codes[axis], ")"); @@ -1417,11 +1388,7 @@ void set_axis_is_at_home(const AxisEnum axis) { #if ENABLED(MORGAN_SCARA) scara_set_axis_is_at_home(axis); #elif ENABLED(DELTA) - current_position[axis] = (axis == Z_AXIS ? delta_height - #if HAS_BED_PROBE - - probe.offset.z - #endif - : base_home_pos(axis)); + current_position[axis] = (axis == Z_AXIS) ? delta_height - TERN0(HAS_BED_PROBE, probe.offset.z) : base_home_pos(axis); #else current_position[axis] = base_home_pos(axis); #endif @@ -1445,13 +1412,9 @@ void set_axis_is_at_home(const AxisEnum axis) { } #endif - #if ENABLED(I2C_POSITION_ENCODERS) - I2CPEM.homed(axis); - #endif + TERN_(I2C_POSITION_ENCODERS, I2CPEM.homed(axis)); - #if ENABLED(BABYSTEP_DISPLAY_TOTAL) - babystep.reset_total(axis); - #endif + TERN_(BABYSTEP_DISPLAY_TOTAL, babystep.reset_total(axis)); #if HAS_POSITION_SHIFT position_shift[axis] = 0; @@ -1478,9 +1441,7 @@ void set_axis_not_trusted(const AxisEnum axis) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_not_trusted(", axis_codes[axis], ")"); - #if ENABLED(I2C_POSITION_ENCODERS) - I2CPEM.unhomed(axis); - #endif + TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); } /** @@ -1596,31 +1557,20 @@ void homeaxis(const AxisEnum axis) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", axis_codes[axis], ")"); - const int axis_home_dir = ( - #if ENABLED(DUAL_X_CARRIAGE) - axis == X_AXIS ? x_home_dir(active_extruder) : - #endif - home_dir(axis) - ); + const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) + ? x_home_dir(active_extruder) : home_dir(axis); // Homing Z towards the bed? Deploy the Z probe or endstop. - #if HOMING_Z_WITH_PROBE - if (axis == Z_AXIS && probe.deploy()) return; - #endif + if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && probe.deploy())) + return; // Set flags for X, Y, Z motor locking #if HAS_EXTRA_ENDSTOPS switch (axis) { - #if ENABLED(X_DUAL_ENDSTOPS) - case X_AXIS: - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - case Y_AXIS: - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - case Z_AXIS: - #endif - stepper.set_separate_multi_axis(true); + TERN_(X_DUAL_ENDSTOPS, case X_AXIS:) + TERN_(Y_DUAL_ENDSTOPS, case Y_AXIS:) + TERN_(Z_MULTI_ENDSTOPS, case Z_AXIS:) + stepper.set_separate_multi_axis(true); default: break; } #endif @@ -1645,11 +1595,9 @@ void homeaxis(const AxisEnum axis) { #endif // When homing Z with probe respect probe clearance + const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(Z_AXIS)); const float bump = axis_home_dir * ( - #if HOMING_Z_WITH_PROBE - (axis == Z_AXIS && home_bump_mm(Z_AXIS)) ? _MAX(Z_CLEARANCE_BETWEEN_PROBES, home_bump_mm(Z_AXIS)) : - #endif - home_bump_mm(axis) + use_probe_bump ? _MAX(Z_CLEARANCE_BETWEEN_PROBES, home_bump_mm(Z_AXIS)) : home_bump_mm(axis) ); // If a second homing move is configured... @@ -1803,16 +1751,10 @@ void homeaxis(const AxisEnum axis) { // Reset flags for X, Y, Z motor locking switch (axis) { default: break; - #if ENABLED(X_DUAL_ENDSTOPS) - case X_AXIS: - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - case Y_AXIS: - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - case Z_AXIS: - #endif - stepper.set_separate_multi_axis(false); + TERN_(X_DUAL_ENDSTOPS, case X_AXIS:) + TERN_(Y_DUAL_ENDSTOPS, case Y_AXIS:) + TERN_(Z_MULTI_ENDSTOPS, case Z_AXIS:) + stepper.set_separate_multi_axis(false); } #endif @@ -1868,9 +1810,8 @@ void homeaxis(const AxisEnum axis) { #if ENABLED(SENSORLESS_HOMING) planner.synchronize(); - #if IS_CORE - if (axis != NORMAL_AXIS) safe_delay(200); // Short delay to allow belts to spring back - #endif + if (TERN0(IS_CORE, axis != NORMAL_AXIS)) + safe_delay(200); // Short delay to allow belts to spring back #endif } #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index ee15205409..eb7bc37894 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -44,13 +44,7 @@ FORCE_INLINE void set_all_unhomed() { axis_homed = 0; } FORCE_INLINE void set_all_unknown() { axis_known_position = 0; } FORCE_INLINE bool homing_needed() { - return !( - #if ENABLED(HOME_AFTER_DEACTIVATE) - all_axes_known() - #else - all_axes_homed() - #endif - ); + return !TERN(HOME_AFTER_DEACTIVATE, all_axes_known, all_axes_homed)(); } // Error margin to work around float imprecision @@ -136,7 +130,7 @@ inline float home_bump_mm(const AxisEnum axis) { #if HAS_WORKSPACE_OFFSET void update_workspace_offset(const AxisEnum axis); #else - #define update_workspace_offset(x) NOOP + inline void update_workspace_offset(const AxisEnum) {} #endif #if HAS_HOTEND_OFFSET diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 5cd83fd8d8..c2a6365417 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -236,17 +236,11 @@ Planner::Planner() { init(); } void Planner::init() { position.reset(); - #if HAS_POSITION_FLOAT - position_float.reset(); - #endif - #if IS_KINEMATIC - position_cart.reset(); - #endif + TERN_(HAS_POSITION_FLOAT, position_float.reset()); + TERN_(IS_KINEMATIC, position_cart.reset()); previous_speed.reset(); previous_nominal_speed_sqr = 0; - #if ABL_PLANAR - bed_level_matrix.set_to_identity(); - #endif + TERN_(ABL_PLANAR, bed_level_matrix.set_to_identity()); clear_block_buffer(); delay_before_delivering = 0; } @@ -738,9 +732,8 @@ block_t* Planner::get_current_block() { // No trapezoid calculated? Don't execute yet. if (TEST(block->flag, BLOCK_BIT_RECALCULATE)) return nullptr; - #if HAS_SPI_LCD - block_buffer_runtime_us -= block->segment_time_us; // We can't be sure how long an active block will take, so don't count it. - #endif + // We can't be sure how long an active block will take, so don't count it. + TERN_(HAS_SPI_LCD, block_buffer_runtime_us -= block->segment_time_us); // As this block is busy, advance the nonbusy block pointer block_buffer_nonbusy = next_block_index(block_buffer_tail); @@ -754,9 +747,7 @@ block_t* Planner::get_current_block() { } // The queue became empty - #if HAS_SPI_LCD - clear_block_buffer_runtime(); // paranoia. Buffer is empty now - so reset accumulated time to zero. - #endif + TERN_(HAS_SPI_LCD, clear_block_buffer_runtime()); // paranoia. Buffer is empty now - so reset accumulated time to zero. return nullptr; } @@ -1304,12 +1295,8 @@ void Planner::check_axes_activity() { #endif #if ENABLED(BARICUDA) - #if HAS_HEATER_1 - tail_valve_pressure = block->valve_pressure; - #endif - #if HAS_HEATER_2 - tail_e_to_p_pressure = block->e_to_p_pressure; - #endif + TERN_(HAS_HEATER_1, tail_valve_pressure = block->valve_pressure); + TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure); #endif #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) @@ -1321,9 +1308,7 @@ void Planner::check_axes_activity() { } else { - #if HAS_CUTTER - cutter.refresh(); - #endif + TERN_(HAS_CUTTER, cutter.refresh()); #if FAN_COUNT > 0 FANS_LOOP(i) @@ -1331,30 +1316,18 @@ void Planner::check_axes_activity() { #endif #if ENABLED(BARICUDA) - #if HAS_HEATER_1 - tail_valve_pressure = baricuda_valve_pressure; - #endif - #if HAS_HEATER_2 - tail_e_to_p_pressure = baricuda_e_to_p_pressure; - #endif + TERN_(HAS_HEATER_1, tail_valve_pressure = baricuda_valve_pressure); + TERN_(HAS_HEATER_2, tail_e_to_p_pressure = baricuda_e_to_p_pressure); #endif } // // Disable inactive axes // - #if ENABLED(DISABLE_X) - if (!axis_active.x) DISABLE_AXIS_X(); - #endif - #if ENABLED(DISABLE_Y) - if (!axis_active.y) DISABLE_AXIS_Y(); - #endif - #if ENABLED(DISABLE_Z) - if (!axis_active.z) DISABLE_AXIS_Z(); - #endif - #if ENABLED(DISABLE_E) - if (!axis_active.e) disable_e_steppers(); - #endif + if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(); + if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(); + if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(); + if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(); // // Update Fan speeds @@ -1391,43 +1364,21 @@ void Planner::check_axes_activity() { #endif #define FAN_SET(F) do{ KICKSTART_FAN(F); _FAN_SET(F); }while(0) - #if HAS_FAN0 - FAN_SET(0); - #endif - #if HAS_FAN1 - FAN_SET(1); - #endif - #if HAS_FAN2 - FAN_SET(2); - #endif - #if HAS_FAN3 - FAN_SET(3); - #endif - #if HAS_FAN4 - FAN_SET(4); - #endif - #if HAS_FAN5 - FAN_SET(5); - #endif - #if HAS_FAN6 - FAN_SET(6); - #endif - #if HAS_FAN7 - FAN_SET(7); - #endif + TERN_(HAS_FAN0, FAN_SET(0)); + TERN_(HAS_FAN1, FAN_SET(1)); + TERN_(HAS_FAN2, FAN_SET(2)); + TERN_(HAS_FAN3, FAN_SET(3)); + TERN_(HAS_FAN4, FAN_SET(4)); + TERN_(HAS_FAN5, FAN_SET(5)); + TERN_(HAS_FAN6, FAN_SET(6)); + TERN_(HAS_FAN7, FAN_SET(7)); #endif // FAN_COUNT > 0 - #if ENABLED(AUTOTEMP) - getHighESpeed(); - #endif + TERN_(AUTOTEMP, getHighESpeed()); #if ENABLED(BARICUDA) - #if HAS_HEATER_1 - analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure); - #endif - #if HAS_HEATER_2 - analogWrite(pin_t(HEATER_2_PIN), tail_e_to_p_pressure); - #endif + TERN_(HAS_HEATER_1, analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, analogWrite(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } @@ -1477,11 +1428,8 @@ void Planner::check_axes_activity() { #if HAS_LEVELING constexpr xy_pos_t level_fulcrum = { - #if ENABLED(Z_SAFE_HOMING) - Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT - #else - X_HOME_POS, Y_HOME_POS - #endif + TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_X_POINT, X_HOME_POS), + TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_Y_POINT, Y_HOME_POS) }; /** @@ -1779,9 +1727,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(extruder)) { position.e = target.e; // Behave as if the move really took place, but ignore E part - #if HAS_POSITION_FLOAT - position_float.e = target_float.e; - #endif + TERN_(HAS_POSITION_FLOAT, position_float.e = target_float.e); de = 0; // no difference SERIAL_ECHO_MSG(STR_ERR_COLD_EXTRUDE_STOP); } @@ -1801,9 +1747,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif if (ignore_e) { position.e = target.e; // Behave as if the move really took place, but ignore E part - #if HAS_POSITION_FLOAT - position_float.e = target_float.e; - #endif + TERN_(HAS_POSITION_FLOAT, position_float.e = target_float.e); de = 0; // no difference SERIAL_ECHO_MSG(STR_ERR_LONG_EXTRUDE_STOP); } @@ -1882,9 +1826,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ struct DistanceMM : abce_float_t { - #if IS_CORE - xyz_pos_t head; - #endif + TERN_(IS_CORE, xyz_pos_t head); } steps_dist_mm; #if IS_CORE #if CORE_IS_XY @@ -1918,9 +1860,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.e = 0.0f; #endif - #if ENABLED(LCD_SHOW_E_TOTAL) - e_move_accumulator += steps_dist_mm.e; - #endif + TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { block->millimeters = (0 @@ -1954,9 +1894,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * A correction function is permitted to add steps to an axis, it * should *never* remove steps! */ - #if ENABLED(BACKLASH_COMPENSATION) - backlash.add_correction_steps(da, db, dc, dm, block); - #endif + TERN_(BACKLASH_COMPENSATION, backlash.add_correction_steps(da, db, dc, dm, block)); } #if EXTRUDERS @@ -1972,9 +1910,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, MIXER_POPULATE_BLOCK(); #endif - #if HAS_CUTTER - block->cutter_power = cutter.power; - #endif + TERN_(HAS_CUTTER, block->cutter_power = cutter.power); #if FAN_COUNT > 0 FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; @@ -2026,9 +1962,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Enable extruder(s) #if EXTRUDERS if (esteps) { - #if ENABLED(AUTO_POWER_CONTROL) - powerManager.power_on(); - #endif + TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder @@ -2195,9 +2129,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (!block->steps.a && !block->steps.b && !block->steps.c) { // convert to: acceleration steps/sec^2 accel = CEIL(settings.retract_acceleration * steps_per_mm); - #if ENABLED(LIN_ADVANCE) - block->use_advance_lead = false; - #endif + TERN_(LIN_ADVANCE, block->use_advance_lead = false); } else { #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \ @@ -2260,9 +2192,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->use_advance_lead = false; else { const uint32_t max_accel_steps_per_s2 = MAX_E_JERK / (extruder_advance_K[active_extruder] * block->e_D_ratio) * steps_per_mm; - #if ENABLED(LA_DEBUG) - if (accel > max_accel_steps_per_s2) SERIAL_ECHOLNPGM("Acceleration limited."); - #endif + if (TERN0(LA_DEBUG, accel > max_accel_steps_per_s2)) + SERIAL_ECHOLNPGM("Acceleration limited."); NOMORE(accel, max_accel_steps_per_s2); } } @@ -2561,22 +2492,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, previous_speed = current_speed; previous_nominal_speed_sqr = block->nominal_speed_sqr; - // Update the position - position = target; - #if HAS_POSITION_FLOAT - position_float = target_float; - #endif + position = target; // Update the position - #if ENABLED(GRADIENT_MIX) - mixer.gradient_control(target_float.z); - #endif + TERN_(HAS_POSITION_FLOAT, position_float = target_float); + TERN_(GRADIENT_MIX, mixer.gradient_control(target_float.z)); + TERN_(POWER_LOSS_RECOVERY, block->sdpos = recovery.command_sdpos()); - #if ENABLED(POWER_LOSS_RECOVERY) - block->sdpos = recovery.command_sdpos(); - #endif + return true; // Movement was accepted - // Movement was accepted - return true; } // _populate_block() /** @@ -2654,15 +2577,9 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con #endif // DRYRUN prevents E moves from taking place - if (DEBUGGING(DRYRUN) - #if ENABLED(CANCEL_OBJECTS) - || cancelable.skipping - #endif - ) { + if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { position.e = target.e; - #if HAS_POSITION_FLOAT - position_float.e = e; - #endif + TERN_(HAS_POSITION_FLOAT, position_float.e = e); } /* <-- add a slash to enable @@ -2697,16 +2614,14 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con //*/ // Queue the movement - if ( - !_buffer_steps(target + if (!_buffer_steps(target #if HAS_POSITION_FLOAT , target_float #endif #if HAS_DIST_MM_ARG , cart_dist_mm #endif - , fr_mm_s, extruder, millimeters - ) + , fr_mm_s, extruder, millimeters) ) return false; stepper.wake_up(); @@ -2730,9 +2645,7 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #endif ) { xyze_pos_t machine = { rx, ry, rz, e }; - #if HAS_POSITION_MODIFIERS - apply_modifiers(machine); - #endif + TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine)); #if IS_KINEMATIC @@ -2785,12 +2698,8 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con */ void Planner::set_machine_position_mm(const float &a, const float &b, const float &c, const float &e) { - #if ENABLED(DISTINCT_E_FACTORS) - last_extruder = active_extruder; - #endif - #if HAS_POSITION_FLOAT - position_float.set(a, b, c, e); - #endif + TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); + TERN_(HAS_POSITION_FLOAT, position_float.set(a, b, c, e)); position.set(LROUND(a * settings.axis_steps_per_mm[A_AXIS]), LROUND(b * settings.axis_steps_per_mm[B_AXIS]), LROUND(c * settings.axis_steps_per_mm[C_AXIS]), @@ -2807,13 +2716,11 @@ void Planner::set_machine_position_mm(const float &a, const float &b, const floa void Planner::set_position_mm(const float &rx, const float &ry, const float &rz, const float &e) { xyze_pos_t machine = { rx, ry, rz, e }; #if HAS_POSITION_MODIFIERS - { apply_modifiers(machine #if HAS_LEVELING , true #endif ); - } #endif #if IS_KINEMATIC position_cart.set(rx, ry, rz, e); @@ -2829,21 +2736,13 @@ void Planner::set_position_mm(const float &rx, const float &ry, const float &rz, */ void Planner::set_e_position_mm(const float &e) { const uint8_t axis_index = E_AXIS_N(active_extruder); - #if ENABLED(DISTINCT_E_FACTORS) - last_extruder = active_extruder; - #endif - #if ENABLED(FWRETRACT) - float e_new = e - fwretract.current_retract[active_extruder]; - #else - const float e_new = e; - #endif + TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); + + const float e_new = e - TERN0(FWRETRACT, fwretract.current_retract[active_extruder]); position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); - #if HAS_POSITION_FLOAT - position_float.e = e_new; - #endif - #if IS_KINEMATIC - position_cart.e = e; - #endif + TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); + TERN_(IS_KINEMATIC, position_cart.e = e); + if (has_blocks_queued()) buffer_sync_block(); else @@ -2863,9 +2762,7 @@ void Planner::reset_acceleration_rates() { if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); } cutoff_long = 4294967295UL / highest_rate; // 0xFFFFFFFFUL - #if HAS_LINEAR_E_JERK - recalculate_max_e_jerk(); - #endif + TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk()); } // Recalculate position, steps_to_mm if settings.axis_steps_per_mm changes! diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 97e907e26b..7ac7d5ade7 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -197,7 +197,9 @@ typedef struct block_t { } block_t; -#define HAS_POSITION_FLOAT ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX, LCD_SHOW_E_TOTAL) +#if ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX, LCD_SHOW_E_TOTAL) + #define HAS_POSITION_FLOAT 1 +#endif #define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1)) @@ -547,44 +549,22 @@ class Planner { #if HAS_POSITION_MODIFIERS FORCE_INLINE static void apply_modifiers(xyze_pos_t &pos #if HAS_LEVELING - , bool leveling = - #if PLANNER_LEVELING - true - #else - false - #endif + , bool leveling = ENABLED(PLANNER_LEVELING) #endif ) { - #if ENABLED(SKEW_CORRECTION) - skew(pos); - #endif - #if HAS_LEVELING - if (leveling) apply_leveling(pos); - #endif - #if ENABLED(FWRETRACT) - apply_retract(pos); - #endif + TERN_(SKEW_CORRECTION, skew(pos)); + TERN_(HAS_LEVELING, if (leveling) apply_leveling(pos)); + TERN_(FWRETRACT, apply_retract(pos)); } FORCE_INLINE static void unapply_modifiers(xyze_pos_t &pos #if HAS_LEVELING - , bool leveling = - #if PLANNER_LEVELING - true - #else - false - #endif + , bool leveling = ENABLED(PLANNER_LEVELING) #endif ) { - #if ENABLED(FWRETRACT) - unapply_retract(pos); - #endif - #if HAS_LEVELING - if (leveling) unapply_leveling(pos); - #endif - #if ENABLED(SKEW_CORRECTION) - unskew(pos); - #endif + TERN_(FWRETRACT, unapply_retract(pos)); + TERN_(HAS_LEVELING, if (leveling) unapply_leveling(pos)); + TERN_(SKEW_CORRECTION, unskew(pos)); } #endif // HAS_POSITION_MODIFIERS diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 3623c88a13..244a2a97b3 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -70,19 +70,14 @@ millis_t PrintCounter::lastDuration; bool PrintCounter::loaded = false; millis_t PrintCounter::deltaDuration() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("deltaDuration")); - #endif - + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("deltaDuration"))); millis_t tmp = lastDuration; lastDuration = duration(); return lastDuration - tmp; } void PrintCounter::incFilamentUsed(float const &amount) { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("incFilamentUsed")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("incFilamentUsed"))); // Refuses to update data if object is not loaded if (!isLoaded()) return; @@ -91,9 +86,7 @@ void PrintCounter::incFilamentUsed(float const &amount) { } void PrintCounter::initStats() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("initStats")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("initStats"))); loaded = true; data = { 0, 0, 0, 0, 0.0 @@ -129,9 +122,7 @@ void PrintCounter::initStats() { #endif void PrintCounter::loadStats() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("loadStats")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("loadStats"))); // Check if the EEPROM block is initialized uint8_t value = 0; @@ -164,9 +155,7 @@ void PrintCounter::loadStats() { } void PrintCounter::saveStats() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("saveStats")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("saveStats"))); // Refuses to save data if object is not loaded if (!isLoaded()) return; @@ -176,9 +165,7 @@ void PrintCounter::saveStats() { persistentStore.write_data(address + sizeof(uint8_t), (uint8_t*)&data, sizeof(printStatistics)); persistentStore.access_finish(); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onConfigurationStoreWritten(true); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onConfigurationStoreWritten(true)); } #if HAS_SERVICE_INTERVALS @@ -239,9 +226,7 @@ void PrintCounter::tick() { static uint32_t update_next; // = 0 if (ELAPSED(now, update_next)) { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("tick")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("tick"))); millis_t delta = deltaDuration(); data.printTime += delta; @@ -267,9 +252,7 @@ void PrintCounter::tick() { // @Override bool PrintCounter::start() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("start")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("start"))); bool paused = isPaused(); @@ -286,9 +269,7 @@ bool PrintCounter::start() { // @Override bool PrintCounter::stop() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("stop")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("stop"))); if (super::stop()) { data.finishedPrints++; @@ -305,9 +286,7 @@ bool PrintCounter::stop() { // @Override void PrintCounter::reset() { - #if ENABLED(DEBUG_PRINTCOUNTER) - debug(PSTR("stop")); - #endif + TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("stop"))); super::reset(); lastDuration = 0; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index a96a9d5e9d..77e70680df 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -134,9 +134,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() LCD_MESSAGEPGM(MSG_MANUAL_DEPLOY_TOUCHMI); ui.return_to_status(); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR)); wait_for_user_response(); ui.reset_status(); ui.goto_screen(prev_screen); @@ -241,23 +239,17 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #if QUIET_PROBING void Probe::set_probing_paused(const bool p) { - #if ENABLED(PROBING_HEATERS_OFF) - thermalManager.pause(p); - #endif - #if ENABLED(PROBING_FANS_OFF) - thermalManager.set_fans_paused(p); - #endif + TERN_(PROBING_HEATERS_OFF, thermalManager.pause(p)); + TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(p)); #if ENABLED(PROBING_STEPPERS_OFF) disable_e_steppers(); #if NONE(DELTA, HOME_AFTER_DEACTIVATE) DISABLE_AXIS_X(); DISABLE_AXIS_Y(); #endif #endif - if (p) safe_delay( + if (p) safe_delay(25 #if DELAY_BEFORE_PROBING > 25 - DELAY_BEFORE_PROBING - #else - 25 + - 25 + DELAY_BEFORE_PROBING #endif ); } @@ -295,22 +287,13 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { serialprintPGM(ds_str); SERIAL_EOL(); - #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe")); - #endif + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); + wait_for_user_response(); ui.reset_status(); - } while( - #if ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED) - true - #else - false - #endif - ); + } while (ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED)); #endif // PAUSE_BEFORE_DEPLOY_STOW @@ -381,11 +364,7 @@ bool Probe::set_deployed(const bool deploy) { do_z_raise(_MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE)); #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) - if (axis_unhomed_error( - #if ENABLED(Z_PROBE_SLED) - _BV(X_AXIS) - #endif - )) { + if (axis_unhomed_error(TERN_(Z_PROBE_SLED, _BV(X_AXIS)))) { SERIAL_ERROR_MSG(STR_STOP_UNHOMED); stop(); return true; @@ -481,9 +460,7 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { endstops.enable(true); #endif - #if QUIET_PROBING - set_probing_paused(true); - #endif + TERN_(QUIET_PROBING, set_probing_paused(true)); // Move down until the probe is triggered do_blocking_move_to_z(z, fr_mm_s); @@ -493,19 +470,11 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { #if BOTH(DELTA, SENSORLESS_PROBING) endstops.trigger_state() & (_BV(X_MIN) | _BV(Y_MIN) | _BV(Z_MIN)) #else - TEST(endstops.trigger_state(), - #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - Z_MIN - #else - Z_MIN_PROBE - #endif - ) + TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE)) #endif ; - #if QUIET_PROBING - set_probing_paused(false); - #endif + TERN_(QUIET_PROBING, set_probing_paused(false)); // Re-enable stealthChop if used. Disable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) @@ -615,9 +584,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { if (try_to_probe(PSTR("SLOW"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_SPEED_SLOW), sanity_check, _MAX(Z_CLEARANCE_MULTI_PROBE, 4) / 2) ) return NAN; - #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - backlash.measure_with_probe(); - #endif + TERN_(MEASURE_BACKLASH_WHEN_PROBING, backlash.measure_with_probe()); const float z = current_position.z; @@ -638,11 +605,8 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #if TOTAL_PROBING > 2 // Small Z raise after all but the last probe - if (p - #if EXTRA_PROBING - < TOTAL_PROBING - 1 - #endif - ) do_blocking_move_to_z(z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + if (TERN(EXTRA_PROBING, p < TOTAL_PROBING - 1, p)) + do_blocking_move_to_z(z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); #endif } diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index c49f939d0f..9ebfb03758 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -32,9 +32,7 @@ HAL_SERVO_LIB servo[NUM_SERVOS]; -#if ENABLED(EDITABLE_SERVO_ANGLES) - uint16_t servo_angles[NUM_SERVOS][2]; -#endif +TERN_(EDITABLE_SERVO_ANGLES, uint16_t servo_angles[NUM_SERVOS][2]); void servo_init() { #if NUM_SERVOS >= 1 && HAS_SERVO_0 diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 94da5f0076..0119c07bea 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -470,11 +470,9 @@ void Stepper::set_directions() { #if HAS_X_DIR SET_STEP_DIR(X); // A #endif - #if HAS_Y_DIR SET_STEP_DIR(Y); // B #endif - #if HAS_Z_DIR SET_STEP_DIR(Z); // C #endif @@ -1503,8 +1501,12 @@ void Stepper::isr() { ENABLE_ISRS(); } -#define ISR_PULSE_CONTROL (MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE) -#define ISR_MULTI_STEPS (ISR_PULSE_CONTROL && DISABLED(I2S_STEPPER_STREAM)) +#if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE + #define ISR_PULSE_CONTROL 1 +#endif +#if ISR_PULSE_CONTROL && DISABLED(I2S_STEPPER_STREAM) + #define ISR_MULTI_STEPS 1 +#endif /** * This phase of the ISR should ONLY create the pulses for the steppers. @@ -1872,13 +1874,9 @@ uint32_t Stepper::block_phase_isr() { return interval; // No more queued movements! } - #if HAS_CUTTER - cutter.apply_power(current_block->cutter_power); - #endif + TERN_(HAS_CUTTER, cutter.apply_power(current_block->cutter_power)); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.info.sdpos = current_block->sdpos; - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.info.sdpos = current_block->sdpos); // Flag all moving axes for proper endstop handling @@ -2024,9 +2022,7 @@ uint32_t Stepper::block_phase_isr() { last_moved_extruder = stepper_extruder; #endif - #if HAS_L64XX - L64XX_OK_to_power_up = true; - #endif + TERN_(HAS_L64XX, L64XX_OK_to_power_up = true); set_directions(); } @@ -2262,17 +2258,11 @@ void Stepper::init() { #endif // Init Microstepping Pins - #if HAS_MICROSTEPS - microstep_init(); - #endif + TERN_(HAS_MICROSTEPS, microstep_init()); // Init Dir Pins - #if HAS_X_DIR - X_DIR_INIT(); - #endif - #if HAS_X2_DIR - X2_DIR_INIT(); - #endif + TERN_(HAS_X_DIR, X_DIR_INIT()); + TERN_(HAS_X2_DIR, X2_DIR_INIT()); #if HAS_Y_DIR Y_DIR_INIT(); #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_DIR @@ -2466,9 +2456,7 @@ void Stepper::init() { set_directions(); #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM - #if HAS_MOTOR_CURRENT_PWM - initialized = true; - #endif + TERN_(HAS_MOTOR_CURRENT_PWM, initialized = true); digipot_init(); #endif } @@ -2948,112 +2936,112 @@ void Stepper::report_positions() { */ void Stepper::microstep_init() { - #if HAS_X_MICROSTEPS + #if HAS_X_MS_PINS SET_OUTPUT(X_MS1_PIN); SET_OUTPUT(X_MS2_PIN); #if PIN_EXISTS(X_MS3) SET_OUTPUT(X_MS3_PIN); #endif #endif - #if HAS_X2_MICROSTEPS + #if HAS_X2_MS_PINS SET_OUTPUT(X2_MS1_PIN); SET_OUTPUT(X2_MS2_PIN); #if PIN_EXISTS(X2_MS3) SET_OUTPUT(X2_MS3_PIN); #endif #endif - #if HAS_Y_MICROSTEPS + #if HAS_Y_MS_PINS SET_OUTPUT(Y_MS1_PIN); SET_OUTPUT(Y_MS2_PIN); #if PIN_EXISTS(Y_MS3) SET_OUTPUT(Y_MS3_PIN); #endif #endif - #if HAS_Y2_MICROSTEPS + #if HAS_Y2_MS_PINS SET_OUTPUT(Y2_MS1_PIN); SET_OUTPUT(Y2_MS2_PIN); #if PIN_EXISTS(Y2_MS3) SET_OUTPUT(Y2_MS3_PIN); #endif #endif - #if HAS_Z_MICROSTEPS + #if HAS_Z_MS_PINS SET_OUTPUT(Z_MS1_PIN); SET_OUTPUT(Z_MS2_PIN); #if PIN_EXISTS(Z_MS3) SET_OUTPUT(Z_MS3_PIN); #endif #endif - #if HAS_Z2_MICROSTEPS + #if HAS_Z2_MS_PINS SET_OUTPUT(Z2_MS1_PIN); SET_OUTPUT(Z2_MS2_PIN); #if PIN_EXISTS(Z2_MS3) SET_OUTPUT(Z2_MS3_PIN); #endif #endif - #if HAS_Z3_MICROSTEPS + #if HAS_Z3_MS_PINS SET_OUTPUT(Z3_MS1_PIN); SET_OUTPUT(Z3_MS2_PIN); #if PIN_EXISTS(Z3_MS3) SET_OUTPUT(Z3_MS3_PIN); #endif #endif - #if HAS_Z4_MICROSTEPS + #if HAS_Z4_MS_PINS SET_OUTPUT(Z4_MS1_PIN); SET_OUTPUT(Z4_MS2_PIN); #if PIN_EXISTS(Z4_MS3) SET_OUTPUT(Z4_MS3_PIN); #endif #endif - #if HAS_E0_MICROSTEPS + #if HAS_E0_MS_PINS SET_OUTPUT(E0_MS1_PIN); SET_OUTPUT(E0_MS2_PIN); #if PIN_EXISTS(E0_MS3) SET_OUTPUT(E0_MS3_PIN); #endif #endif - #if HAS_E1_MICROSTEPS + #if HAS_E1_MS_PINS SET_OUTPUT(E1_MS1_PIN); SET_OUTPUT(E1_MS2_PIN); #if PIN_EXISTS(E1_MS3) SET_OUTPUT(E1_MS3_PIN); #endif #endif - #if HAS_E2_MICROSTEPS + #if HAS_E2_MS_PINS SET_OUTPUT(E2_MS1_PIN); SET_OUTPUT(E2_MS2_PIN); #if PIN_EXISTS(E2_MS3) SET_OUTPUT(E2_MS3_PIN); #endif #endif - #if HAS_E3_MICROSTEPS + #if HAS_E3_MS_PINS SET_OUTPUT(E3_MS1_PIN); SET_OUTPUT(E3_MS2_PIN); #if PIN_EXISTS(E3_MS3) SET_OUTPUT(E3_MS3_PIN); #endif #endif - #if HAS_E4_MICROSTEPS + #if HAS_E4_MS_PINS SET_OUTPUT(E4_MS1_PIN); SET_OUTPUT(E4_MS2_PIN); #if PIN_EXISTS(E4_MS3) SET_OUTPUT(E4_MS3_PIN); #endif #endif - #if HAS_E5_MICROSTEPS + #if HAS_E5_MS_PINS SET_OUTPUT(E5_MS1_PIN); SET_OUTPUT(E5_MS2_PIN); #if PIN_EXISTS(E5_MS3) SET_OUTPUT(E5_MS3_PIN); #endif #endif - #if HAS_E6_MICROSTEPS + #if HAS_E6_MS_PINS SET_OUTPUT(E6_MS1_PIN); SET_OUTPUT(E6_MS2_PIN); #if PIN_EXISTS(E6_MS3) SET_OUTPUT(E6_MS3_PIN); #endif #endif - #if HAS_E7_MICROSTEPS + #if HAS_E7_MS_PINS SET_OUTPUT(E7_MS1_PIN); SET_OUTPUT(E7_MS2_PIN); #if PIN_EXISTS(E7_MS3) @@ -3068,188 +3056,188 @@ void Stepper::report_positions() { void Stepper::microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2, const int8_t ms3) { if (ms1 >= 0) switch (driver) { - #if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS + #if HAS_X_MS_PINS || HAS_X2_MS_PINS case 0: - #if HAS_X_MICROSTEPS + #if HAS_X_MS_PINS WRITE(X_MS1_PIN, ms1); #endif - #if HAS_X2_MICROSTEPS + #if HAS_X2_MS_PINS WRITE(X2_MS1_PIN, ms1); #endif break; #endif - #if HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS + #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS case 1: - #if HAS_Y_MICROSTEPS + #if HAS_Y_MS_PINS WRITE(Y_MS1_PIN, ms1); #endif - #if HAS_Y2_MICROSTEPS + #if HAS_Y2_MS_PINS WRITE(Y2_MS1_PIN, ms1); #endif break; #endif - #if HAS_SOME_Z_MICROSTEPS + #if HAS_SOME_Z_MS_PINS case 2: - #if HAS_Z_MICROSTEPS + #if HAS_Z_MS_PINS WRITE(Z_MS1_PIN, ms1); #endif - #if HAS_Z2_MICROSTEPS + #if HAS_Z2_MS_PINS WRITE(Z2_MS1_PIN, ms1); #endif - #if HAS_Z3_MICROSTEPS + #if HAS_Z3_MS_PINS WRITE(Z3_MS1_PIN, ms1); #endif - #if HAS_Z4_MICROSTEPS + #if HAS_Z4_MS_PINS WRITE(Z4_MS1_PIN, ms1); #endif break; #endif - #if HAS_E0_MICROSTEPS + #if HAS_E0_MS_PINS case 3: WRITE(E0_MS1_PIN, ms1); break; #endif - #if HAS_E1_MICROSTEPS + #if HAS_E1_MS_PINS case 4: WRITE(E1_MS1_PIN, ms1); break; #endif - #if HAS_E2_MICROSTEPS + #if HAS_E2_MS_PINS case 5: WRITE(E2_MS1_PIN, ms1); break; #endif - #if HAS_E3_MICROSTEPS + #if HAS_E3_MS_PINS case 6: WRITE(E3_MS1_PIN, ms1); break; #endif - #if HAS_E4_MICROSTEPS + #if HAS_E4_MS_PINS case 7: WRITE(E4_MS1_PIN, ms1); break; #endif - #if HAS_E5_MICROSTEPS + #if HAS_E5_MS_PINS case 8: WRITE(E5_MS1_PIN, ms1); break; #endif - #if HAS_E6_MICROSTEPS + #if HAS_E6_MS_PINS case 9: WRITE(E6_MS1_PIN, ms1); break; #endif - #if HAS_E7_MICROSTEPS + #if HAS_E7_MS_PINS case 10: WRITE(E7_MS1_PIN, ms1); break; #endif } if (ms2 >= 0) switch (driver) { - #if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS + #if HAS_X_MS_PINS || HAS_X2_MS_PINS case 0: - #if HAS_X_MICROSTEPS + #if HAS_X_MS_PINS WRITE(X_MS2_PIN, ms2); #endif - #if HAS_X2_MICROSTEPS + #if HAS_X2_MS_PINS WRITE(X2_MS2_PIN, ms2); #endif break; #endif - #if HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS + #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS case 1: - #if HAS_Y_MICROSTEPS + #if HAS_Y_MS_PINS WRITE(Y_MS2_PIN, ms2); #endif - #if HAS_Y2_MICROSTEPS + #if HAS_Y2_MS_PINS WRITE(Y2_MS2_PIN, ms2); #endif break; #endif - #if HAS_SOME_Z_MICROSTEPS + #if HAS_SOME_Z_MS_PINS case 2: - #if HAS_Z_MICROSTEPS + #if HAS_Z_MS_PINS WRITE(Z_MS2_PIN, ms2); #endif - #if HAS_Z2_MICROSTEPS + #if HAS_Z2_MS_PINS WRITE(Z2_MS2_PIN, ms2); #endif - #if HAS_Z3_MICROSTEPS + #if HAS_Z3_MS_PINS WRITE(Z3_MS2_PIN, ms2); #endif - #if HAS_Z4_MICROSTEPS + #if HAS_Z4_MS_PINS WRITE(Z4_MS2_PIN, ms2); #endif break; #endif - #if HAS_E0_MICROSTEPS + #if HAS_E0_MS_PINS case 3: WRITE(E0_MS2_PIN, ms2); break; #endif - #if HAS_E1_MICROSTEPS + #if HAS_E1_MS_PINS case 4: WRITE(E1_MS2_PIN, ms2); break; #endif - #if HAS_E2_MICROSTEPS + #if HAS_E2_MS_PINS case 5: WRITE(E2_MS2_PIN, ms2); break; #endif - #if HAS_E3_MICROSTEPS + #if HAS_E3_MS_PINS case 6: WRITE(E3_MS2_PIN, ms2); break; #endif - #if HAS_E4_MICROSTEPS + #if HAS_E4_MS_PINS case 7: WRITE(E4_MS2_PIN, ms2); break; #endif - #if HAS_E5_MICROSTEPS + #if HAS_E5_MS_PINS case 8: WRITE(E5_MS2_PIN, ms2); break; #endif - #if HAS_E6_MICROSTEPS + #if HAS_E6_MS_PINS case 9: WRITE(E6_MS2_PIN, ms2); break; #endif - #if HAS_E7_MICROSTEPS + #if HAS_E7_MS_PINS case 10: WRITE(E7_MS2_PIN, ms2); break; #endif } if (ms3 >= 0) switch (driver) { - #if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS + #if HAS_X_MS_PINS || HAS_X2_MS_PINS case 0: - #if HAS_X_MICROSTEPS && PIN_EXISTS(X_MS3) + #if HAS_X_MS_PINS && PIN_EXISTS(X_MS3) WRITE(X_MS3_PIN, ms3); #endif - #if HAS_X2_MICROSTEPS && PIN_EXISTS(X2_MS3) + #if HAS_X2_MS_PINS && PIN_EXISTS(X2_MS3) WRITE(X2_MS3_PIN, ms3); #endif break; #endif - #if HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS + #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS case 1: - #if HAS_Y_MICROSTEPS && PIN_EXISTS(Y_MS3) + #if HAS_Y_MS_PINS && PIN_EXISTS(Y_MS3) WRITE(Y_MS3_PIN, ms3); #endif - #if HAS_Y2_MICROSTEPS && PIN_EXISTS(Y2_MS3) + #if HAS_Y2_MS_PINS && PIN_EXISTS(Y2_MS3) WRITE(Y2_MS3_PIN, ms3); #endif break; #endif - #if HAS_SOME_Z_MICROSTEPS + #if HAS_SOME_Z_MS_PINS case 2: - #if HAS_Z_MICROSTEPS && PIN_EXISTS(Z_MS3) + #if HAS_Z_MS_PINS && PIN_EXISTS(Z_MS3) WRITE(Z_MS3_PIN, ms3); #endif - #if HAS_Z2_MICROSTEPS && PIN_EXISTS(Z2_MS3) + #if HAS_Z2_MS_PINS && PIN_EXISTS(Z2_MS3) WRITE(Z2_MS3_PIN, ms3); #endif - #if HAS_Z3_MICROSTEPS && PIN_EXISTS(Z3_MS3) + #if HAS_Z3_MS_PINS && PIN_EXISTS(Z3_MS3) WRITE(Z3_MS3_PIN, ms3); #endif - #if HAS_Z4_MICROSTEPS && PIN_EXISTS(Z4_MS3) + #if HAS_Z4_MS_PINS && PIN_EXISTS(Z4_MS3) WRITE(Z4_MS3_PIN, ms3); #endif break; #endif - #if HAS_E0_MICROSTEPS && PIN_EXISTS(E0_MS3) + #if HAS_E0_MS_PINS && PIN_EXISTS(E0_MS3) case 3: WRITE(E0_MS3_PIN, ms3); break; #endif - #if HAS_E1_MICROSTEPS && PIN_EXISTS(E1_MS3) + #if HAS_E1_MS_PINS && PIN_EXISTS(E1_MS3) case 4: WRITE(E1_MS3_PIN, ms3); break; #endif - #if HAS_E2_MICROSTEPS && PIN_EXISTS(E2_MS3) + #if HAS_E2_MS_PINS && PIN_EXISTS(E2_MS3) case 5: WRITE(E2_MS3_PIN, ms3); break; #endif - #if HAS_E3_MICROSTEPS && PIN_EXISTS(E3_MS3) + #if HAS_E3_MS_PINS && PIN_EXISTS(E3_MS3) case 6: WRITE(E3_MS3_PIN, ms3); break; #endif - #if HAS_E4_MICROSTEPS && PIN_EXISTS(E4_MS3) + #if HAS_E4_MS_PINS && PIN_EXISTS(E4_MS3) case 7: WRITE(E4_MS3_PIN, ms3); break; #endif - #if HAS_E5_MICROSTEPS && PIN_EXISTS(E5_MS3) + #if HAS_E5_MS_PINS && PIN_EXISTS(E5_MS3) case 8: WRITE(E5_MS3_PIN, ms3); break; #endif - #if HAS_E6_MICROSTEPS && PIN_EXISTS(E6_MS3) + #if HAS_E6_MS_PINS && PIN_EXISTS(E6_MS3) case 9: WRITE(E6_MS3_PIN, ms3); break; #endif - #if HAS_E7_MICROSTEPS && PIN_EXISTS(E7_MS3) + #if HAS_E7_MS_PINS && PIN_EXISTS(E7_MS3) case 10: WRITE(E7_MS3_PIN, ms3); break; #endif } @@ -3288,7 +3276,7 @@ void Stepper::report_positions() { void Stepper::microstep_readings() { SERIAL_ECHOLNPGM("MS1|MS2|MS3 Pins"); - #if HAS_X_MICROSTEPS + #if HAS_X_MS_PINS SERIAL_ECHOPGM("X: "); SERIAL_CHAR('0' + READ(X_MS1_PIN), '0' + READ(X_MS2_PIN) #if PIN_EXISTS(X_MS3) @@ -3296,7 +3284,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_Y_MICROSTEPS + #if HAS_Y_MS_PINS SERIAL_ECHOPGM("Y: "); SERIAL_CHAR('0' + READ(Y_MS1_PIN), '0' + READ(Y_MS2_PIN) #if PIN_EXISTS(Y_MS3) @@ -3304,7 +3292,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_Z_MICROSTEPS + #if HAS_Z_MS_PINS SERIAL_ECHOPGM("Z: "); SERIAL_CHAR('0' + READ(Z_MS1_PIN), '0' + READ(Z_MS2_PIN) #if PIN_EXISTS(Z_MS3) @@ -3312,7 +3300,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E0_MICROSTEPS + #if HAS_E0_MS_PINS SERIAL_ECHOPGM("E0: "); SERIAL_CHAR('0' + READ(E0_MS1_PIN), '0' + READ(E0_MS2_PIN) #if PIN_EXISTS(E0_MS3) @@ -3320,7 +3308,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E1_MICROSTEPS + #if HAS_E1_MS_PINS SERIAL_ECHOPGM("E1: "); SERIAL_CHAR('0' + READ(E1_MS1_PIN), '0' + READ(E1_MS2_PIN) #if PIN_EXISTS(E1_MS3) @@ -3328,7 +3316,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E2_MICROSTEPS + #if HAS_E2_MS_PINS SERIAL_ECHOPGM("E2: "); SERIAL_CHAR('0' + READ(E2_MS1_PIN), '0' + READ(E2_MS2_PIN) #if PIN_EXISTS(E2_MS3) @@ -3336,7 +3324,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E3_MICROSTEPS + #if HAS_E3_MS_PINS SERIAL_ECHOPGM("E3: "); SERIAL_CHAR('0' + READ(E3_MS1_PIN), '0' + READ(E3_MS2_PIN) #if PIN_EXISTS(E3_MS3) @@ -3344,7 +3332,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E4_MICROSTEPS + #if HAS_E4_MS_PINS SERIAL_ECHOPGM("E4: "); SERIAL_CHAR('0' + READ(E4_MS1_PIN), '0' + READ(E4_MS2_PIN) #if PIN_EXISTS(E4_MS3) @@ -3352,7 +3340,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E5_MICROSTEPS + #if HAS_E5_MS_PINS SERIAL_ECHOPGM("E5: "); SERIAL_CHAR('0' + READ(E5_MS1_PIN), '0' + READ(E5_MS2_PIN) #if PIN_EXISTS(E5_MS3) @@ -3360,7 +3348,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E6_MICROSTEPS + #if HAS_E6_MS_PINS SERIAL_ECHOPGM("E6: "); SERIAL_CHAR('0' + READ(E6_MS1_PIN), '0' + READ(E6_MS2_PIN) #if PIN_EXISTS(E6_MS3) @@ -3368,7 +3356,7 @@ void Stepper::report_positions() { #endif ); #endif - #if HAS_E7_MICROSTEPS + #if HAS_E7_MS_PINS SERIAL_ECHOPGM("E7: "); SERIAL_CHAR('0' + READ(E7_MS1_PIN), '0' + READ(E7_MS2_PIN) #if PIN_EXISTS(E7_MS3) diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index 2ddbfe62e3..c0702dc12d 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -33,21 +33,13 @@ #include "indirection.h" void restore_stepper_drivers() { - #if HAS_TRINAMIC_CONFIG - restore_trinamic_drivers(); - #endif + TERN_(HAS_TRINAMIC_CONFIG, restore_trinamic_drivers()); } void reset_stepper_drivers() { #if HAS_DRIVER(TMC26X) tmc26x_init_to_defaults(); #endif - - #if HAS_L64XX - L64xxManager.init_to_defaults(); - #endif - - #if HAS_TRINAMIC_CONFIG - reset_trinamic_drivers(); - #endif + TERN_(HAS_L64XX, L64xxManager.init_to_defaults()); + TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers()); } diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 1440c24cf8..100d660f2c 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -140,9 +140,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; chopconf.intpol = INTERPOLATE; chopconf.hend = chopper_timing.hend + 3; chopconf.hstrt = chopper_timing.hstrt - 1; - #if ENABLED(SQUARE_WAVE_STEPPING) - chopconf.dedge = true; - #endif + TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); st.rms_current(mA, HOLD_MULTIPLIER); @@ -181,9 +179,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; chopconf.intpol = INTERPOLATE; chopconf.hend = chopper_timing.hend + 3; chopconf.hstrt = chopper_timing.hstrt - 1; - #if ENABLED(SQUARE_WAVE_STEPPING) - chopconf.dedge = true; - #endif + TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); st.rms_current(mA, HOLD_MULTIPLIER); @@ -475,9 +471,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; chopconf.intpol = INTERPOLATE; chopconf.hend = chopper_timing.hend + 3; chopconf.hstrt = chopper_timing.hstrt - 1; - #if ENABLED(SQUARE_WAVE_STEPPING) - chopconf.dedge = true; - #endif + TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); st.rms_current(mA, HOLD_MULTIPLIER); @@ -523,9 +517,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; chopconf.intpol = INTERPOLATE; chopconf.hend = chopper_timing.hend + 3; chopconf.hstrt = chopper_timing.hstrt - 1; - #if ENABLED(SQUARE_WAVE_STEPPING) - chopconf.dedge = true; - #endif + TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); st.rms_current(mA, HOLD_MULTIPLIER); @@ -569,15 +561,10 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; st.sdoff(0); st.rms_current(mA); st.microsteps(microsteps); - #if ENABLED(SQUARE_WAVE_STEPPING) - st.dedge(true); - #endif + TERN_(SQUARE_WAVE_STEPPING, st.dedge(true)); st.intpol(INTERPOLATE); st.diss2g(true); // Disable short to ground protection. Too many false readings? - - #if ENABLED(TMC_DEBUG) - st.rdsel(0b01); - #endif + TERN_(TMC_DEBUG, st.rdsel(0b01)); } #endif // TMC2660 @@ -592,9 +579,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; chopconf.intpol = INTERPOLATE; chopconf.hend = chopper_timing.hend + 3; chopconf.hstrt = chopper_timing.hstrt - 1; - #if ENABLED(SQUARE_WAVE_STEPPING) - chopconf.dedge = true; - #endif + TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); st.rms_current(mA, HOLD_MULTIPLIER); @@ -633,9 +618,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; chopconf.intpol = INTERPOLATE; chopconf.hend = chopper_timing.hend + 3; chopconf.hstrt = chopper_timing.hstrt - 1; - #if ENABLED(SQUARE_WAVE_STEPPING) - chopconf.dedge = true; - #endif + TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); st.rms_current(mA, HOLD_MULTIPLIER); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index c72eb6f371..fc86061ccc 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -236,15 +236,9 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #ifdef BED_MAXTEMP int16_t Temperature::maxtemp_raw_BED = HEATER_BED_RAW_HI_TEMP; #endif - #if WATCH_BED - bed_watch_t Temperature::watch_bed; // = { 0 } - #endif - #if DISABLED(PIDTEMPBED) - millis_t Temperature::next_bed_check_ms; - #endif - #if HEATER_IDLE_HANDLER - hotend_idle_t Temperature::bed_idle; // = { 0 } - #endif + TERN_(WATCH_BED, bed_watch_t Temperature::watch_bed); // = { 0 } + TERN(PIDTEMPBED,, millis_t Temperature::next_bed_check_ms); + TERN_(HEATER_IDLE_HANDLER, hotend_idle_t Temperature::bed_idle); // = { 0 } #endif // HAS_HEATED_BED #if HAS_TEMP_CHAMBER @@ -403,15 +397,11 @@ volatile bool Temperature::raw_temps_ready = false; bool heated = false; #endif - #if HAS_AUTO_FAN - next_auto_fan_check_ms = next_temp_ms + 2500UL; - #endif + TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); if (target > GHV(BED_MAXTEMP - 10, temp_range[heater].maxtemp - 15)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); return; } @@ -427,9 +417,7 @@ volatile bool Temperature::raw_temps_ready = false; LEDColor color = ONHEATINGSTART(); #endif - #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) - adaptive_fan_slowing = false; - #endif + TERN_(NO_FAN_SLOWING_IN_PID_TUNING, adaptive_fan_slowing = false); // PID Tuning loop while (wait_for_heatup) { @@ -525,9 +513,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); break; } @@ -562,9 +548,7 @@ volatile bool Temperature::raw_temps_ready = false; #define MAX_CYCLE_TIME_PID_AUTOTUNE 20L #endif if (((ms - t1) + (ms - t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); - #endif + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; } @@ -610,12 +594,9 @@ volatile bool Temperature::raw_temps_ready = false; #endif } - #if ENABLED(PRINTER_EVENT_LEDS) - printerEventLEDs.onPidTuningDone(color); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); - #endif + TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); + + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_DONE)); goto EXIT_M303; } @@ -624,17 +605,12 @@ volatile bool Temperature::raw_temps_ready = false; disable_all_heaters(); - #if ENABLED(PRINTER_EVENT_LEDS) - printerEventLEDs.onPidTuningDone(color); - #endif - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); - #endif + TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); + + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_DONE)); EXIT_M303: - #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) - adaptive_fan_slowing = true; - #endif + TERN_(NO_FAN_SLOWING_IN_PID_TUNING, adaptive_fan_slowing = true); return; } @@ -653,11 +629,7 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { case H_CHAMBER: return temp_chamber.soft_pwm_amount; #endif default: - return (0 - #if HAS_HOTEND - + temp_hotend[heater_id].soft_pwm_amount - #endif - ); + return TERN0(HAS_HOTEND, temp_hotend[heater_id].soft_pwm_amount); } } @@ -771,19 +743,16 @@ void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, static uint8_t killed = 0; - if (IsRunning() - #if BOGUS_TEMPERATURE_GRACE_PERIOD - && killed == 2 - #endif - ) { + if (IsRunning() && TERN1(BOGUS_TEMPERATURE_GRACE_PERIOD, killed == 2)) { SERIAL_ERROR_START(); serialprintPGM(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); - if (heater >= 0) SERIAL_ECHO((int)heater); - #if HAS_HEATED_CHAMBER - else if (heater == H_CHAMBER) SERIAL_ECHOPGM(STR_HEATER_CHAMBER); - #endif - else SERIAL_ECHOPGM(STR_HEATER_BED); + if (heater >= 0) + SERIAL_ECHO((int)heater); + else if (TERN0(HAS_HEATED_CHAMBER, heater == H_CHAMBER)) + SERIAL_ECHOPGM(STR_HEATER_CHAMBER); + else + SERIAL_ECHOPGM(STR_HEATER_BED); SERIAL_EOL(); } @@ -839,9 +808,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { if (temp_hotend[ee].target == 0 || pid_error < -(PID_FUNCTIONAL_RANGE) - #if HEATER_IDLE_HANDLER - || hotend_idle[ee].timed_out - #endif + || TERN0(HEATER_IDLE_HANDLER, hotend_idle[ee].timed_out) ) { pid_output = 0; pid_reset[ee] = true; @@ -1015,9 +982,8 @@ void Temperature::manage_heater() { if (!inited) return watchdog_refresh(); #endif - #if ENABLED(EMERGENCY_PARSER) - if (emergency_parser.killed_by_M112) kill(M112_KILL_STR, nullptr, true); - #endif + if (TERN0(EMERGENCY_PARSER, emergency_parser.killed_by_M112)) + kill(M112_KILL_STR, nullptr, true); if (!raw_temps_ready) return; @@ -1043,9 +1009,7 @@ void Temperature::manage_heater() { _temp_error((heater_ind_t)e, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); #endif - #if HEATER_IDLE_HANDLER - hotend_idle[e].update(ms); - #endif + TERN_(HEATER_IDLE_HANDLER, hotend_idle[e].update(ms)); #if ENABLED(THERMAL_PROTECTION_HOTENDS) // Check for thermal runaway @@ -1106,7 +1070,10 @@ void Temperature::manage_heater() { } #endif // WATCH_BED - #define PAUSE_CHANGE_REQD BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #define PAUSE_CHANGE_REQD 1 + #endif + #if PAUSE_CHANGE_REQD static bool last_pause_state; #endif @@ -1115,23 +1082,15 @@ void Temperature::manage_heater() { #if DISABLED(PIDTEMPBED) if (PENDING(ms, next_bed_check_ms) - #if PAUSE_CHANGE_REQD - && paused == last_pause_state - #endif + && TERN1(PAUSE_CHANGE_REQD, paused == last_pause_state) ) break; next_bed_check_ms = ms + BED_CHECK_INTERVAL; - #if PAUSE_CHANGE_REQD - last_pause_state = paused; - #endif + TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused); #endif - #if HEATER_IDLE_HANDLER - bed_idle.update(ms); - #endif + TERN_(HEATER_IDLE_HANDLER, bed_idle.update(ms)); - #if HAS_THERMALLY_PROTECTED_BED - thermal_runaway_protection(tr_state_machine_bed, temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS); - #endif + TERN_(HAS_THERMALLY_PROTECTED_BED, thermal_runaway_protection(tr_state_machine_bed, temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS)); #if HEATER_IDLE_HANDLER if (bed_idle.timed_out) { @@ -1207,9 +1166,7 @@ void Temperature::manage_heater() { WRITE_HEATER_CHAMBER(LOW); } - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - thermal_runaway_protection(tr_state_machine_chamber, temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS); - #endif + TERN_(THERMAL_PROTECTION_CHAMBER, thermal_runaway_protection(tr_state_machine_chamber, temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS)); } // TODO: Implement true PID pwm @@ -1302,36 +1259,16 @@ void Temperature::manage_heater() { SERIAL_ECHOPAIR_F(" C", t.sh_c_coeff, 9); SERIAL_ECHOPGM(" ; "); serialprintPGM( - #if ENABLED(HEATER_0_USER_THERMISTOR) - t_index == CTI_HOTEND_0 ? PSTR("HOTEND 0") : - #endif - #if ENABLED(HEATER_1_USER_THERMISTOR) - t_index == CTI_HOTEND_1 ? PSTR("HOTEND 1") : - #endif - #if ENABLED(HEATER_2_USER_THERMISTOR) - t_index == CTI_HOTEND_2 ? PSTR("HOTEND 2") : - #endif - #if ENABLED(HEATER_3_USER_THERMISTOR) - t_index == CTI_HOTEND_3 ? PSTR("HOTEND 3") : - #endif - #if ENABLED(HEATER_4_USER_THERMISTOR) - t_index == CTI_HOTEND_4 ? PSTR("HOTEND 4") : - #endif - #if ENABLED(HEATER_5_USER_THERMISTOR) - t_index == CTI_HOTEND_5 ? PSTR("HOTEND 5") : - #endif - #if ENABLED(HEATER_6_USER_THERMISTOR) - t_index == CTI_HOTEND_6 ? PSTR("HOTEND 6") : - #endif - #if ENABLED(HEATER_7_USER_THERMISTOR) - t_index == CTI_HOTEND_7 ? PSTR("HOTEND 7") : - #endif - #if ENABLED(HEATER_BED_USER_THERMISTOR) - t_index == CTI_BED ? PSTR("BED") : - #endif - #if ENABLED(HEATER_CHAMBER_USER_THERMISTOR) - t_index == CTI_CHAMBER ? PSTR("CHAMBER") : - #endif + TERN_(HEATER_0_USER_THERMISTOR, t_index == CTI_HOTEND_0 ? PSTR("HOTEND 0") :) + TERN_(HEATER_1_USER_THERMISTOR, t_index == CTI_HOTEND_1 ? PSTR("HOTEND 1") :) + TERN_(HEATER_2_USER_THERMISTOR, t_index == CTI_HOTEND_2 ? PSTR("HOTEND 2") :) + TERN_(HEATER_3_USER_THERMISTOR, t_index == CTI_HOTEND_3 ? PSTR("HOTEND 3") :) + TERN_(HEATER_4_USER_THERMISTOR, t_index == CTI_HOTEND_4 ? PSTR("HOTEND 4") :) + TERN_(HEATER_5_USER_THERMISTOR, t_index == CTI_HOTEND_5 ? PSTR("HOTEND 5") :) + TERN_(HEATER_6_USER_THERMISTOR, t_index == CTI_HOTEND_6 ? PSTR("HOTEND 6") :) + TERN_(HEATER_7_USER_THERMISTOR, t_index == CTI_HOTEND_7 ? PSTR("HOTEND 7") :) + TERN_(HEATER_BED_USER_THERMISTOR, t_index == CTI_BED ? PSTR("BED") :) + TERN_(HEATER_CHAMBER_USER_THERMISTOR, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) nullptr ); SERIAL_EOL(); @@ -1387,12 +1324,7 @@ void Temperature::manage_heater() { // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. float Temperature::analog_to_celsius_hotend(const int raw, const uint8_t e) { - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - if (e > HOTENDS) - #else - if (e >= HOTENDS) - #endif - { + if (e > HOTENDS - DISABLED(TEMP_SENSOR_1_AS_REDUNDANT)) { SERIAL_ERROR_START(); SERIAL_ECHO((int)e); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); @@ -1577,21 +1509,11 @@ void Temperature::updateTemperaturesFromRawValues() { #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif - #if HAS_HEATED_BED - temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw); - #endif - #if HAS_TEMP_CHAMBER - temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw); - #endif - #if HAS_TEMP_PROBE - temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw); - #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - redundant_temperature = analog_to_celsius_hotend(redundant_temperature_raw, 1); - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - filwidth.update_measured_mm(); - #endif + TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); + TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(TEMP_SENSOR_1_AS_REDUNDANT, redundant_temperature = analog_to_celsius_hotend(redundant_temperature_raw, 1)); + TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_measured_mm()); // Reset the watchdog on good temperature measurement watchdog_refresh(); @@ -1637,9 +1559,7 @@ void Temperature::updateTemperaturesFromRawValues() { */ void Temperature::init() { - #if ENABLED(MAX6675_IS_MAX31865) - max31865.begin(MAX31865_2WIRE); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - #endif + TERN_(MAX6675_IS_MAX31865, max31865.begin(MAX31865_2WIRE)); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE #if EARLY_WATCHDOG // Flag that the thermalManager should be running @@ -1931,9 +1851,7 @@ void Temperature::init() { #endif #endif - #if ENABLED(PROBING_HEATERS_OFF) - paused = false; - #endif + TERN_(PROBING_HEATERS_OFF, paused = false); } #if WATCH_HOTENDS @@ -2004,9 +1922,7 @@ void Temperature::init() { #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart if ((heater_id >= 0 && hotend_idle[heater_id].timed_out) - #if HAS_HEATED_BED - || (heater_id < 0 && bed_idle.timed_out) - #endif + || TERN0(HAS_HEATED_BED, (heater_id < 0 && bed_idle.timed_out)) ) { sm.state = TRInactive; tr_target_temperature[heater_index] = 0; @@ -2065,26 +1981,16 @@ void Temperature::init() { void Temperature::disable_all_heaters() { - #if ENABLED(AUTOTEMP) - planner.autotemp_enabled = false; - #endif + TERN_(AUTOTEMP, planner.autotemp_enabled = false); #if HAS_HOTEND HOTEND_LOOP() setTargetHotend(0, e); #endif - - #if HAS_HEATED_BED - setTargetBed(0); - #endif - - #if HAS_HEATED_CHAMBER - setTargetChamber(0); - #endif + TERN_(HAS_HEATED_BED, setTargetBed(0)); + TERN_(HAS_HEATED_CHAMBER, setTargetChamber(0)); // Unpause and reset everything - #if ENABLED(PROBING_HEATERS_OFF) - pause(false); - #endif + TERN_(PROBING_HEATERS_OFF, pause(false)); #define DISABLE_HEATER(N) { \ setTargetHotend(0, N); \ @@ -2115,13 +2021,8 @@ void Temperature::disable_all_heaters() { #if HAS_HOTEND HOTEND_LOOP() if (degTargetHotend(e) > (EXTRUDE_MINTEMP) / 2) return true; #endif - #if HAS_HEATED_BED - if (degTargetBed() > BED_MINTEMP) return true; - #endif - #if HAS_HEATED_CHAMBER - if (degTargetChamber() > CHAMBER_MINTEMP) return true; - #endif - return false; + return TERN0(HAS_HEATED_BED, degTargetBed() > BED_MINTEMP) + || TERN0(HAS_HEATED_CHAMBER, degTargetChamber() > CHAMBER_MINTEMP); } void Temperature::check_timer_autostart(const bool can_start, const bool can_stop) { @@ -2143,16 +2044,12 @@ void Temperature::disable_all_heaters() { if (p != paused) { paused = p; if (p) { - HOTEND_LOOP() hotend_idle[e].expire(); // timeout immediately - #if HAS_HEATED_BED - bed_idle.expire(); // timeout immediately - #endif + HOTEND_LOOP() hotend_idle[e].expire(); // Timeout immediately + TERN_(HAS_HEATED_BED, bed_idle.expire()); // Timeout immediately } else { HOTEND_LOOP() reset_hotend_idle_timer(e); - #if HAS_HEATED_BED - reset_bed_idle_timer(); - #endif + TERN_(HAS_HEATED_BED, reset_bed_idle_timer()); } } } @@ -2303,46 +2200,19 @@ void Temperature::update_raw_temperatures() { #endif #endif - #if HAS_TEMP_ADC_2 - temp_hotend[2].update(); - #endif - #if HAS_TEMP_ADC_3 - temp_hotend[3].update(); - #endif - #if HAS_TEMP_ADC_4 - temp_hotend[4].update(); - #endif - #if HAS_TEMP_ADC_5 - temp_hotend[5].update(); - #endif - #if HAS_TEMP_ADC_6 - temp_hotend[6].update(); - #endif - #if HAS_TEMP_ADC_7 - temp_hotend[7].update(); - #endif + TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); + TERN_(HAS_TEMP_ADC_3, temp_hotend[3].update()); + TERN_(HAS_TEMP_ADC_4, temp_hotend[4].update()); + TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update()); + TERN_(HAS_TEMP_ADC_6, temp_hotend[6].update()); + TERN_(HAS_TEMP_ADC_7, temp_hotend[7].update()); + TERN_(HAS_HEATED_BED, temp_bed.update()); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.update()); + TERN_(HAS_TEMP_PROBE, temp_probe.update()); - #if HAS_HEATED_BED - temp_bed.update(); - #endif - - #if HAS_TEMP_CHAMBER - temp_chamber.update(); - #endif - - #if HAS_TEMP_PROBE - temp_probe.update(); - #endif - - #if HAS_JOY_ADC_X - joystick.x.update(); - #endif - #if HAS_JOY_ADC_Y - joystick.y.update(); - #endif - #if HAS_JOY_ADC_Z - joystick.z.update(); - #endif + TERN_(HAS_JOY_ADC_X, joystick.x.update()); + TERN_(HAS_JOY_ADC_Y, joystick.y.update()); + TERN_(HAS_JOY_ADC_Z, joystick.z.update()); raw_temps_ready = true; } @@ -2353,38 +2223,20 @@ void Temperature::readings_ready() { if (!raw_temps_ready) update_raw_temperatures(); // Filament Sensor - can be read any time since IIR filtering is used - #if ENABLED(FILAMENT_WIDTH_SENSOR) - filwidth.reading_ready(); - #endif + TERN_(FILAMENT_WIDTH_SENSOR, filwidth.reading_ready()); #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].reset(); - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - temp_hotend[1].reset(); - #endif + TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_hotend[1].reset()); #endif - #if HAS_HEATED_BED - temp_bed.reset(); - #endif + TERN_(HAS_HEATED_BED, temp_bed.reset()); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.reset()); + TERN_(HAS_TEMP_PROBE, temp_probe.reset()); - #if HAS_TEMP_CHAMBER - temp_chamber.reset(); - #endif - - #if HAS_TEMP_PROBE - temp_probe.reset(); - #endif - - #if HAS_JOY_ADC_X - joystick.x.reset(); - #endif - #if HAS_JOY_ADC_Y - joystick.y.reset(); - #endif - #if HAS_JOY_ADC_Z - joystick.z.reset(); - #endif + TERN_(HAS_JOY_ADC_X, joystick.x.reset()); + TERN_(HAS_JOY_ADC_Y, joystick.y.reset()); + TERN_(HAS_JOY_ADC_Z, joystick.z.reset()); #if HAS_HOTEND @@ -2412,9 +2264,7 @@ void Temperature::readings_ready() { if (tdir) { const int16_t rawtemp = temp_hotend[e].raw * tdir; // normal direction, +rawtemp, else -rawtemp const bool heater_on = (temp_hotend[e].target > 0 - #if ENABLED(PIDTEMP) - || temp_hotend[e].soft_pwm_amount > 0 - #endif + || TERN0(PIDTEMP, temp_hotend[e].soft_pwm_amount) > 0 ); if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_ind_t)e); if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { @@ -2438,10 +2288,8 @@ void Temperature::readings_ready() { #else #define BEDCMP(A,B) ((A)>=(B)) #endif - const bool bed_on = (temp_bed.target > 0) - #if ENABLED(PIDTEMPBED) - || (temp_bed.soft_pwm_amount > 0) - #endif + const bool bed_on = temp_bed.target > 0 + || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount) > 0 ; if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); if (bed_on && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); @@ -2774,10 +2622,8 @@ void Temperature::tick() { #if HAS_HOTEND HOTEND_LOOP() soft_pwm_hotend[e].dec(); #endif - #if HAS_HEATED_BED - soft_pwm_bed.dec(); - #endif - } // ((pwm_count >> SOFT_PWM_SCALE) & 0x3F) == 0 + TERN_(HAS_HEATED_BED, soft_pwm_bed.dec()); + } #endif // SLOW_PWM_HEATERS @@ -3218,9 +3064,7 @@ void Temperature::tick() { if (wait_for_heatup) { ui.reset_status(); - #if ENABLED(PRINTER_EVENT_LEDS) - printerEventLEDs.onHeatingDone(); - #endif + TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onHeatingDone()); } return wait_for_heatup; diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 981615c1b4..f9f2fbc071 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -173,7 +173,9 @@ enum ADCSensorState : char { #define unscalePID_d(d) ( float(d) * PID_dT ) #endif -#define G26_CLICK_CAN_CANCEL (HAS_LCD_MENU && ENABLED(G26_MESH_VALIDATION)) +#if BOTH(HAS_LCD_MENU, G26_MESH_VALIDATION) + #define G26_CLICK_CAN_CANCEL 1 +#endif // A temperature sensor typedef struct TempInfo { @@ -317,30 +319,16 @@ class Temperature { public: - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - #define HOTEND_TEMPS (HOTENDS + 1) - #else - #define HOTEND_TEMPS HOTENDS - #endif #if HAS_HOTEND + #define HOTEND_TEMPS (HOTENDS + ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)) static hotend_info_t temp_hotend[HOTEND_TEMPS]; #endif - #if HAS_HEATED_BED - static bed_info_t temp_bed; - #endif - #if HAS_TEMP_PROBE - static probe_info_t temp_probe; - #endif - #if HAS_TEMP_CHAMBER - static chamber_info_t temp_chamber; - #endif + TERN_(HAS_HEATED_BED, static bed_info_t temp_bed); + TERN_(HAS_TEMP_PROBE, static probe_info_t temp_probe); + TERN_(HAS_TEMP_CHAMBER, static chamber_info_t temp_chamber); - #if ENABLED(AUTO_POWER_E_FANS) - static uint8_t autofan_speed[HOTENDS]; - #endif - #if ENABLED(AUTO_POWER_CHAMBER_FAN) - static uint8_t chamberfan_speed; - #endif + TERN_(AUTO_POWER_E_FANS, static uint8_t autofan_speed[HOTENDS]); + TERN_(AUTO_POWER_CHAMBER_FAN, static uint8_t chamberfan_speed); #if ENABLED(FAN_SOFT_PWM) static uint8_t soft_pwm_amount_fan[FAN_COUNT], @@ -367,25 +355,17 @@ class Temperature { #if HEATER_IDLE_HANDLER static hotend_idle_t hotend_idle[HOTENDS]; - #if HAS_HEATED_BED - static hotend_idle_t bed_idle; - #endif - #if HAS_HEATED_CHAMBER - static hotend_idle_t chamber_idle; - #endif + TERN_(HAS_HEATED_BED, static hotend_idle_t bed_idle); + TERN_(HAS_HEATED_CHAMBER, static hotend_idle_t chamber_idle); #endif private: - #if EARLY_WATCHDOG - static bool inited; // If temperature controller is running - #endif + TERN_(EARLY_WATCHDOG, static bool inited); // If temperature controller is running static volatile bool raw_temps_ready; - #if WATCH_HOTENDS - static hotend_watch_t watch_hotend[HOTENDS]; - #endif + TERN_(WATCH_HOTENDS, static hotend_watch_t watch_hotend[HOTENDS]); #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) static uint16_t redundant_temperature_raw; @@ -397,17 +377,11 @@ class Temperature { static lpq_ptr_t lpq_ptr; #endif - #if HOTENDS - static temp_range_t temp_range[HOTENDS]; - #endif + TERN_(HAS_HOTEND, static temp_range_t temp_range[HOTENDS]); #if HAS_HEATED_BED - #if WATCH_BED - static bed_watch_t watch_bed; - #endif - #if DISABLED(PIDTEMPBED) - static millis_t next_bed_check_ms; - #endif + TERN_(WATCH_BED, static bed_watch_t watch_bed); + TERN(PIDTEMPBED,,static millis_t next_bed_check_ms); #ifdef BED_MINTEMP static int16_t mintemp_raw_BED; #endif @@ -417,9 +391,7 @@ class Temperature { #endif #if HAS_HEATED_CHAMBER - #if WATCH_CHAMBER - static chamber_watch_t watch_chamber; - #endif + TERN_(WATCH_CHAMBER, static chamber_watch_t watch_chamber); static millis_t next_chamber_check_ms; #ifdef CHAMBER_MINTEMP static int16_t mintemp_raw_CHAMBER; @@ -437,13 +409,9 @@ class Temperature { static millis_t preheat_end_time[HOTENDS]; #endif - #if HAS_AUTO_FAN - static millis_t next_auto_fan_check_ms; - #endif + TERN_(HAS_AUTO_FAN, static millis_t next_auto_fan_check_ms); - #if ENABLED(PROBING_HEATERS_OFF) - static bool paused; - #endif + TERN_(PROBING_HEATERS_OFF, static bool paused); public: #if HAS_ADC_BUTTONS @@ -451,9 +419,7 @@ class Temperature { static uint8_t ADCKey_count; #endif - #if ENABLED(PID_EXTRUSION_SCALING) - static int16_t lpq_len; - #endif + TERN_(PID_EXTRUSION_SCALING, static int16_t lpq_len); /** * Instance Methods @@ -524,9 +490,7 @@ class Temperature { static constexpr inline uint8_t fanPercent(const uint8_t speed) { return ui8_to_percent(speed); } - #if ENABLED(ADAPTIVE_FAN_SLOWING) - static uint8_t fan_speed_scaler[FAN_COUNT]; - #endif + TERN_(ADAPTIVE_FAN_SLOWING, static uint8_t fan_speed_scaler[FAN_COUNT]); static inline uint8_t scaledFanSpeed(const uint8_t target, const uint8_t fs) { UNUSED(target); // Potentially unused! @@ -593,29 +557,17 @@ class Temperature { //deg=degreeCelsius FORCE_INLINE static float degHotend(const uint8_t E_NAME) { - return (0 - #if HOTENDS - + temp_hotend[HOTEND_INDEX].celsius - #endif - ); + return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].celsius); } #if ENABLED(SHOW_TEMP_ADC_VALUES) FORCE_INLINE static int16_t rawHotendTemp(const uint8_t E_NAME) { - return (0 - #if HOTENDS - + temp_hotend[HOTEND_INDEX].raw - #endif - ); + return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].raw); } #endif FORCE_INLINE static int16_t degTargetHotend(const uint8_t E_NAME) { - return (0 - #if HOTENDS - + temp_hotend[HOTEND_INDEX].target - #endif - ); + return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].target); } #if WATCH_HOTENDS @@ -634,9 +586,7 @@ class Temperature { else if (temp_hotend[ee].target == 0) start_preheat_time(ee); #endif - #if ENABLED(AUTO_POWER_CONTROL) - powerManager.power_on(); - #endif + TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); temp_hotend[ee].target = _MIN(celsius, temp_range[ee].maxtemp - 15); start_watching_hotend(ee); } @@ -680,9 +630,7 @@ class Temperature { #endif static void setTargetBed(const int16_t celsius) { - #if ENABLED(AUTO_POWER_CONTROL) - powerManager.power_on(); - #endif + TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); temp_bed.target = #ifdef BED_MAXTEMP _MIN(celsius, BED_MAXTEMP - 10) @@ -784,9 +732,7 @@ class Temperature { */ #if ENABLED(PIDTEMP) FORCE_INLINE static void updatePID() { - #if ENABLED(PID_EXTRUSION_SCALING) - last_e_position = 0; - #endif + TERN_(PID_EXTRUSION_SCALING, last_e_position = 0); } #endif @@ -831,9 +777,7 @@ class Temperature { #endif #endif - #if HAS_DISPLAY - static void set_heating_message(const uint8_t e); - #endif + TERN_(HAS_DISPLAY, static void set_heating_message(const uint8_t e)); private: static void update_raw_temperatures(); @@ -862,13 +806,9 @@ class Temperature { static float get_pid_output_hotend(const uint8_t e); - #if ENABLED(PIDTEMPBED) - static float get_pid_output_bed(); - #endif + TERN_(PIDTEMPBED, static float get_pid_output_bed()); - #if HAS_HEATED_CHAMBER - static float get_pid_output_chamber(); - #endif + TERN_(HAS_HEATED_CHAMBER, static float get_pid_output_chamber()); static void _temp_error(const heater_ind_t e, PGM_P const serial_msg, PGM_P const lcd_msg); static void min_temp_error(const heater_ind_t e); @@ -885,15 +825,9 @@ class Temperature { TRState state = TRInactive; } tr_state_machine_t; - #if ENABLED(THERMAL_PROTECTION_HOTENDS) - static tr_state_machine_t tr_state_machine[HOTENDS]; - #endif - #if HAS_THERMALLY_PROTECTED_BED - static tr_state_machine_t tr_state_machine_bed; - #endif - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - static tr_state_machine_t tr_state_machine_chamber; - #endif + TERN_(THERMAL_PROTECTION_HOTENDS, static tr_state_machine_t tr_state_machine[HOTENDS]); + TERN_(HAS_THERMALLY_PROTECTED_BED, static tr_state_machine_t tr_state_machine_bed); + TERN_(THERMAL_PROTECTION_CHAMBER, static tr_state_machine_t tr_state_machine_chamber); static void thermal_runaway_protection(tr_state_machine_t &state, const float ¤t, const float &target, const heater_ind_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index b30e72eace..23925d630c 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -152,11 +152,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a const float oldx = current_position.x, grabpos = mpe_settings.parking_xpos[new_tool] + (new_tool ? mpe_settings.grab_distance : -mpe_settings.grab_distance), - offsetcompensation = (0 - #if HAS_HOTEND_OFFSET - + hotend_offset[active_extruder].x * mpe_settings.compensation_factor - #endif - ); + offsetcompensation = TERN0(HAS_HOTEND_OFFSET, hotend_offset[active_extruder].x * mpe_settings.compensation_factor); if (axis_unhomed_error(_BV(X_AXIS))) return; @@ -322,9 +318,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a planner.synchronize(); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(4) Engage magnetic field"); - #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) - pe_activate_solenoid(active_extruder); // Just save power for inverted magnets - #endif + // Just save power for inverted magnets + TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, pe_activate_solenoid(active_extruder)); pe_activate_solenoid(new_tool); // STEP 5 @@ -341,11 +336,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 6 - current_position.x = midpos - #if HAS_HOTEND_OFFSET - - hotend_offset[new_tool].x - #endif - ; + current_position.x = midpos - TERN0(HAS_HOTEND_OFFSET, hotend_offset[new_tool].x); if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("(6) Move midway between hotends", current_position); @@ -358,9 +349,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a else { // nomove == true // Only engage magnetic field for new extruder pe_activate_solenoid(new_tool); - #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) - pe_activate_solenoid(active_extruder); // Just save power for inverted magnets - #endif + // Just save power for inverted magnets + TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, pe_activate_solenoid(active_extruder)); } } @@ -775,9 +765,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a */ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { - #if ENABLED(MAGNETIC_SWITCHING_TOOLHEAD) - if (new_tool == active_extruder) return; - #endif + if (TERN0(MAGNETIC_SWITCHING_TOOLHEAD, new_tool == active_extruder)) + return; #if ENABLED(MIXING_EXTRUDER) @@ -826,9 +815,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("No move (not homed)"); } - #if HAS_LCD_MENU - if (!no_move) ui.return_to_status(); - #endif + TERN_(HAS_LCD_MENU, if (!no_move) ui.return_to_status()); #if ENABLED(DUAL_X_CARRIAGE) const bool idex_full_control = dual_x_carriage_mode == DXC_FULL_CONTROL_MODE; @@ -873,9 +860,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool != old_tool) { - #if SWITCHING_NOZZLE_TWO_SERVOS - raise_nozzle(old_tool); - #endif + TERN_(SWITCHING_NOZZLE_TWO_SERVOS, raise_nozzle(old_tool)); REMEMBER(fr, feedrate_mm_s, XY_PROBE_FEEDRATE_MM_S); @@ -902,9 +887,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { NOMORE(current_position.z, soft_endstop.max.z); #endif fast_line_to_current(Z_AXIS); - #if ENABLED(TOOLCHANGE_PARK) - current_position = toolchange_settings.change_point; - #endif + TERN_(TOOLCHANGE_PARK, current_position = toolchange_settings.change_point); planner.buffer_line(current_position, feedrate_mm_s, old_tool); planner.synchronize(); } @@ -912,9 +895,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if HAS_HOTEND_OFFSET xyz_pos_t diff = hotend_offset[new_tool] - hotend_offset[old_tool]; - #if ENABLED(DUAL_X_CARRIAGE) - diff.x = 0; - #endif + TERN_(DUAL_X_CARRIAGE, diff.x = 0); #else constexpr xyz_pos_t diff{0}; #endif @@ -981,9 +962,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { singlenozzle_temp[old_tool] = thermalManager.temp_hotend[0].target; if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { thermalManager.setTargetHotend(singlenozzle_temp[new_tool], 0); - #if HAS_DISPLAY - thermalManager.set_heating_message(0); - #endif + TERN_(HAS_DISPLAY, thermalManager.set_heating_message(0)); (void)thermalManager.wait_for_hotend(0, false); // Wait for heating or cooling } #endif @@ -1030,9 +1009,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { } else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move back skipped"); - #if ENABLED(DUAL_X_CARRIAGE) - active_extruder_parked = false; - #endif + TERN_(DUAL_X_CARRIAGE, active_extruder_parked = false); } #if ENABLED(SWITCHING_NOZZLE) else { @@ -1041,13 +1018,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { } #endif - #if ENABLED(PRUSA_MMU2) - mmu2.tool_change(new_tool); - #endif + TERN_(PRUSA_MMU2, mmu2.tool_change(new_tool)); - #if SWITCHING_NOZZLE_TWO_SERVOS - lower_nozzle(new_tool); - #endif + TERN_(SWITCHING_NOZZLE_TWO_SERVOS, lower_nozzle(new_tool)); } // (new_tool != old_tool) @@ -1068,9 +1041,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { move_extruder_servo(active_extruder); #endif - #if HAS_FANMUX - fanmux_switch(active_extruder); - #endif + TERN_(HAS_FANMUX, fanmux_switch(active_extruder)); #ifdef EVENT_GCODE_AFTER_TOOLCHANGE if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 17c173d052..0e915a0415 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -31,9 +31,7 @@ float swap_length, extra_prime; int16_t prime_speed, retract_speed; #endif - #if ENABLED(TOOLCHANGE_PARK) - xy_pos_t change_point; - #endif + TERN_(TOOLCHANGE_PARK, xy_pos_t change_point); float z_raise; } toolchange_settings_t; @@ -93,13 +91,9 @@ #endif #endif -#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) - void est_init(); -#endif +TERN_(ELECTROMAGNETIC_SWITCHING_TOOLHEAD, void est_init()); -#if ENABLED(SWITCHING_TOOLHEAD) - void swt_init(); -#endif +TERN_(SWITCHING_TOOLHEAD, void swt_init()); /** * Perform a tool-change, which may result in moving the diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 6f2557cda8..bf80657a2f 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -407,16 +407,12 @@ void CardReader::manage_media() { ui.media_changed(old_stat, stat); // Update the UI if (stat) { - #if ENABLED(SDCARD_EEPROM_EMULATION) - settings.first_load(); - #endif - if (old_stat == 2) { // First mount? - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.check(); - #else - beginautostart(); // Look for autostart files soon - #endif - } + TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); + if (old_stat == 2) // First mount? + TERN(POWER_LOSS_RECOVERY, + recovery.check(), // Check for PLR file. (If not there it will beginautostart) + beginautostart() // Look for auto0.g on the next loop + ); } } } @@ -438,25 +434,15 @@ void CardReader::openAndPrintFile(const char *name) { void CardReader::startFileprint() { if (isMounted()) { flag.sdprinting = true; - #if SD_RESORT - flush_presort(); - #endif + TERN_(SD_RESORT, flush_presort()); } } -void CardReader::endFilePrint( - #if SD_RESORT - const bool re_sort/*=false*/ - #endif -) { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - did_pause_print = 0; - #endif +void CardReader::endFilePrint(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { + TERN_(ADVANCED_PAUSE_FEATURE, did_pause_print = 0); flag.sdprinting = flag.abort_sd_printing = false; if (isFileOpen()) file.close(); - #if SD_RESORT - if (re_sort) presort(); - #endif + TERN_(SD_RESORT, if (re_sort) presort()); } void CardReader::openLogFile(char * const path) { @@ -590,9 +576,7 @@ void CardReader::openFileWrite(char * const path) { if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { flag.saving = true; selectFileByName(fname); - #if ENABLED(EMERGENCY_PARSER) - emergency_parser.disable(); - #endif + TERN_(EMERGENCY_PARSER, emergency_parser.disable()); echo_write_to_file(fname); ui.set_status(fname); } @@ -615,9 +599,7 @@ void CardReader::removeFile(const char * const name) { if (file.remove(curDir, fname)) { SERIAL_ECHOLNPAIR("File deleted:", fname); sdpos = 0; - #if ENABLED(SDCARD_SORT_ALPHA) - presort(); - #endif + TERN_(SDCARD_SORT_ALPHA, presort()); } else SERIAL_ECHOLNPAIR("Deletion failed, File: ", fname, "."); @@ -664,15 +646,10 @@ void CardReader::checkautostart() { if (autostart_index < 0 || flag.sdprinting) return; if (!isMounted()) mount(); - #if ENABLED(SDCARD_EEPROM_EMULATION) - else settings.first_load(); - #endif + TERN_(SDCARD_EEPROM_EMULATION, else settings.first_load()); - if (isMounted() - #if ENABLED(POWER_LOSS_RECOVERY) - && !recovery.valid() // Don't run auto#.g when a resume file exists - #endif - ) { + // Don't run auto#.g when a PLR file exists + if (isMounted() && TERN1(POWER_LOSS_RECOVERY, !recovery.valid())) { char autoname[8]; sprintf_P(autoname, PSTR("auto%c.g"), autostart_index + '0'); dir_t p; @@ -699,9 +676,7 @@ void CardReader::closefile(const bool store_location) { file.close(); flag.saving = flag.logging = false; sdpos = 0; - #if ENABLED(EMERGENCY_PARSER) - emergency_parser.enable(); - #endif + TERN_(EMERGENCY_PARSER, emergency_parser.enable()); if (store_location) { //future: store printer state, filename and position for continuing a stopped print @@ -824,9 +799,7 @@ void CardReader::cd(const char * relpath) { flag.workDirIsRoot = false; if (workDirDepth < MAX_DIR_DEPTH) workDirParents[workDirDepth++] = workDir; - #if ENABLED(SDCARD_SORT_ALPHA) - presort(); - #endif + TERN_(SDCARD_SORT_ALPHA, presort()); } else { SERIAL_ECHO_START(); @@ -837,9 +810,7 @@ void CardReader::cd(const char * relpath) { int8_t CardReader::cdup() { if (workDirDepth > 0) { // At least 1 dir has been saved workDir = --workDirDepth ? workDirParents[workDirDepth - 1] : root; // Use parent, or root if none - #if ENABLED(SDCARD_SORT_ALPHA) - presort(); - #endif + TERN_(SDCARD_SORT_ALPHA, presort()); } if (!workDirDepth) flag.workDirIsRoot = true; return workDirDepth; @@ -848,9 +819,7 @@ int8_t CardReader::cdup() { void CardReader::cdroot() { workDir = root; flag.workDirIsRoot = true; - #if ENABLED(SDCARD_SORT_ALPHA) - presort(); - #endif + TERN_(SDCARD_SORT_ALPHA, presort()); } #if ENABLED(SDCARD_SORT_ALPHA) @@ -859,12 +828,8 @@ void CardReader::cdroot() { * Get the name of a file in the working directory by sort-index */ void CardReader::getfilename_sorted(const uint16_t nr) { - selectFileByIndex( - #if ENABLED(SDSORT_GCODE) - sort_alpha && - #endif - (nr < sort_count) ? sort_order[nr] : nr - ); + selectFileByIndex(TERN1(SDSORT_GCODE, sort_alpha) && (nr < sort_count) + ? sort_order[nr] : nr); } #if ENABLED(SDSORT_USES_RAM) @@ -910,9 +875,7 @@ void CardReader::cdroot() { flush_presort(); // Sorting may be turned off - #if ENABLED(SDSORT_GCODE) - if (!sort_alpha) return; - #endif + if (TERN0(SDSORT_GCODE, !sort_alpha)) return; // If there are files, sort up to the limit uint16_t fileCnt = countFilesInWorkDir(); @@ -923,9 +886,7 @@ void CardReader::cdroot() { NOMORE(fileCnt, uint16_t(SDSORT_LIMIT)); // Sort order is always needed. May be static or dynamic. - #if ENABLED(SDSORT_DYNAMIC_RAM) - sort_order = new uint8_t[fileCnt]; - #endif + TERN_(SDSORT_DYNAMIC_RAM, sort_order = new uint8_t[fileCnt]); // Use RAM to store the entire directory during pre-sort. // SDSORT_LIMIT should be set to prevent over-allocation. @@ -963,11 +924,7 @@ void CardReader::cdroot() { // Init sort order. for (uint16_t i = 0; i < fileCnt; i++) { - sort_order[i] = ( - #if ENABLED(SDCARD_RATHERRECENTFIRST) - fileCnt - 1 - - #endif - i); + sort_order[i] = TERN(SDCARD_RATHERRECENTFIRST, fileCnt - 1 - i, i); // If using RAM then read all filenames now. #if ENABLED(SDSORT_USES_RAM) selectFileByIndex(i); @@ -991,9 +948,7 @@ void CardReader::cdroot() { #if DISABLED(SDSORT_USES_RAM) selectFileByIndex(o1); // Pre-fetch the first entry and save it strcpy(name1, longest_filename()); // so the loop only needs one fetch - #if HAS_FOLDER_SORTING - bool dir1 = flag.filenameIsDir; - #endif + TERN_(HAS_FOLDER_SORTING, bool dir1 = flag.filenameIsDir); #endif for (uint16_t j = 0; j < i; ++j) { @@ -1045,9 +1000,7 @@ void CardReader::cdroot() { // The next o1 is the current o2. No new fetch needed. o1 = o2; #if DISABLED(SDSORT_USES_RAM) - #if HAS_FOLDER_SORTING - dir1 = dir2; - #endif + TERN_(HAS_FOLDER_SORTING, dir1 = dir2); strcpy(name1, name2); #endif } @@ -1058,9 +1011,7 @@ void CardReader::cdroot() { #if ENABLED(SDSORT_USES_RAM) && DISABLED(SDSORT_CACHE_NAMES) #if ENABLED(SDSORT_DYNAMIC_RAM) for (uint16_t i = 0; i < fileCnt; ++i) free(sortnames[i]); - #if HAS_FOLDER_SORTING - free(isDir); - #endif + TERN_(HAS_FOLDER_SORTING, free(isDir)); #endif #endif } @@ -1127,9 +1078,7 @@ void CardReader::fileHasFinished() { else { endFilePrint(); - #if ENABLED(SDCARD_SORT_ALPHA) - presort(); - #endif + TERN_(SDCARD_SORT_ALPHA, presort()); marlin_state = MF_SD_COMPLETE; } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 1fee807495..ef1912c8bd 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -25,7 +25,9 @@ #if ENABLED(SDSUPPORT) -#define SD_RESORT BOTH(SDCARD_SORT_ALPHA, SDSORT_DYNAMIC_RAM) +#if BOTH(SDCARD_SORT_ALPHA, SDSORT_DYNAMIC_RAM) + #define SD_RESORT 1 +#endif #define MAX_DIR_DEPTH 10 // Maximum folder depth #define MAXDIRNAMELENGTH 8 // DOS folder name size @@ -113,11 +115,7 @@ public: static void getAbsFilename(char *dst); static void printFilename(); static void startFileprint(); - static void endFilePrint( - #if SD_RESORT - const bool re_sort=false - #endif - ); + static void endFilePrint(TERN_(SD_RESORT, const bool re_sort=false)); static void report_status(); static inline void pauseSDPrint() { flag.sdprinting = false; } static inline bool isPaused() { return isFileOpen() && !flag.sdprinting; } From 468b813bc1f2ce5026736f27f9e48c36fefa9e9e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ond=C5=99ej=20Nov=C3=BD?= Date: Wed, 22 Apr 2020 23:43:06 +0200 Subject: [PATCH 0237/1454] Better ooze prevention during pause (#17625) --- Marlin/src/feature/pause.cpp | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 3eb786752c..64ef914372 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -541,11 +541,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep * - a nozzle timed out, or * - the nozzle is already heated. * - Display "wait for print to resume" + * - Retract to prevent oozing + * - Move the nozzle back to resume_position + * - Unretract * - Re-prime the nozzle... * - FWRETRACT: Recover/prime from the prior G10. * - !FWRETRACT: Retract by resume_position.e, if negative. * Not sure how this logic comes into use. - * - Move the nozzle back to resume_position * - Sync the planner E to resume_position.e * - Send host action for resume, if configured * - Resume the current SD print job, if any @@ -574,6 +576,18 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_RESUME)); + // Retract to prevent oozing + unscaled_e_move(-(PAUSE_PARK_RETRACT_LENGTH), feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); + + // Move XY to starting position, then Z + do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + + // Move Z_AXIS to saved position + do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + + // Unretract + unscaled_e_move(PAUSE_PARK_RETRACT_LENGTH, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); + // Intelligent resuming #if ENABLED(FWRETRACT) // If retracted before goto pause @@ -583,13 +597,6 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le // If resume_position is negative if (resume_position.e < 0) unscaled_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); - - // Move XY to starting position, then Z - do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); - - // Move Z_AXIS to saved position - do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); - #if ADVANCED_PAUSE_RESUME_PRIME != 0 unscaled_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); #endif @@ -611,10 +618,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR)); #if ENABLED(SDSUPPORT) - if (did_pause_print) { - card.startFileprint(); - --did_pause_print; - } + if (did_pause_print) { card.startFileprint(); --did_pause_print; } #endif #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && FAN_COUNT > 0 From c3aeed0dcce0203684cf951adbbdcddff2f87670 Mon Sep 17 00:00:00 2001 From: Alexander Amelkin Date: Thu, 23 Apr 2020 00:43:43 +0300 Subject: [PATCH 0238/1454] Prevent SKR Pro bootloader corruption (#17657) Co-authored-by: Scott Lahteine --- buildroot/share/PlatformIO/boards/BigTree_Btt002.json | 1 + buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json | 1 + 2 files changed, 2 insertions(+) diff --git a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json index 8ef3b77ea8..9012d107bc 100644 --- a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json +++ b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json @@ -37,6 +37,7 @@ "dfu", "jlink" ], + "offset_address": "0x8008000", "require_upload_port": true, "use_1200bps_touch": false, "wait_for_upload_port": false diff --git a/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json b/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json index a949e00a35..1b5aee4b8e 100644 --- a/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json +++ b/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json @@ -37,6 +37,7 @@ "dfu", "jlink" ], + "offset_address": "0x8008000", "require_upload_port": true, "use_1200bps_touch": false, "wait_for_upload_port": false From f263787f071f0f0e55cb3ba400262bc6aed231e9 Mon Sep 17 00:00:00 2001 From: RudolphRiedel <31180093+RudolphRiedel@users.noreply.github.com> Date: Wed, 22 Apr 2020 23:47:29 +0200 Subject: [PATCH 0239/1454] Fix ExtUI 0 --- .../ftdi_eve_touch_ui/screens/interface_settings_screen.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 401a1298c6..d893518275 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -157,9 +157,7 @@ void InterfaceSettingsScreen::onIdle() { CommandProcessor cmd; switch (cmd.track_tag(value)) { case 2: - screen_data.InterfaceSettingsScreen.brightness = float(value) * 128 / 0xFFFF; - if (screen_data.InterfaceSettingsScreen.brightness > 1) - screen_data.InterfaceSettingsScreen.brightness = 1; + screen_data.InterfaceSettingsScreen.brightness = constrain((value * 128UL) / 0xFFFF, 1, 11); CLCD::set_brightness(screen_data.InterfaceSettingsScreen.brightness); SaveSettingsDialogBox::settingsChanged(); break; From 19873f04d4f5c3b675ad8a28deae2df6e50f5ab1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Apr 2020 12:30:58 -0500 Subject: [PATCH 0240/1454] Fix M100 compile warning --- Marlin/src/gcode/calibrate/M100.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 6b8a0de528..fb04420e54 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -116,13 +116,18 @@ // Utility functions // -// Location of a variable on its stack frame. Returns a value above -// the stack (once the function returns to the caller). -char* top_of_stack() { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wreturn-local-addr" + +// Location of a variable in its stack frame. +// The returned address will be above the stack (after it returns). +char *top_of_stack() { char x; return &x + 1; // x is pulled on return; } +#pragma GCC diagnostic pop + // Count the number of test bytes at the specified location. inline int32_t count_test_bytes(const char * const start_free_memory) { for (uint32_t i = 0; i < 32000; i++) From e222ba4c813cd6769bc67f5eeb5ca0ae08a78c2e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Apr 2020 18:45:45 -0500 Subject: [PATCH 0241/1454] Prevent DUE / Spindle conflict Fixes #17449 --- Marlin/Configuration_adv.h | 4 ++-- Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 96eff59619..cc28c050a6 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2694,11 +2694,11 @@ /** * Speed / Power can be set ('M3 S') and displayed in terms of: - * - PWM (S0 - S255) + * - PWM255 (S0 - S255) * - PERCENT (S0 - S100) * - RPM (S0 - S50000) Best for use with a spindle */ - #define CUTTER_POWER_DISPLAY PWM + #define CUTTER_POWER_DISPLAY PWM255 /** * Relative mode uses relative range (SPEED_POWER_MIN to SPEED_POWER_MAX) instead of normal range (0 to SPEED_POWER_MAX) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 56c7ce7463..9a2b9f2a0b 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -139,7 +139,7 @@ // #if EITHER(SPINDLE_FEATURE, LASER_FEATURE) #define HAS_CUTTER 1 - #define _CUTTER_DISP_PWM 1 + #define _CUTTER_DISP_PWM255 1 #define _CUTTER_DISP_PERCENT 2 #define _CUTTER_DISP_RPM 3 #define _CUTTER_DISP(V) _CAT(_CUTTER_DISP_, V) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 223967f818..6a0d0bd8e6 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2784,8 +2784,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if HAS_CUTTER #ifndef CUTTER_POWER_DISPLAY #error "CUTTER_POWER_DISPLAY is required with a spindle or laser. Please update your Configuration_adv.h." - #elif !CUTTER_DISPLAY_IS(PWM) && !CUTTER_DISPLAY_IS(PERCENT) && !CUTTER_DISPLAY_IS(RPM) - #error "CUTTER_POWER_DISPLAY must be PWM, PERCENT, or RPM. Please update your Configuration_adv.h." + #elif !CUTTER_DISPLAY_IS(PWM255) && !CUTTER_DISPLAY_IS(PERCENT) && !CUTTER_DISPLAY_IS(RPM) + #error "CUTTER_POWER_DISPLAY must be PWM255, PERCENT, or RPM. Please update your Configuration_adv.h." #endif #if ENABLED(LASER_POWER_INLINE) From 4dce03fa42867773fb680733ea1c9615faf8eaef Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 23 Apr 2020 00:03:05 +0000 Subject: [PATCH 0242/1454] [cron] Bump distribution date (2020-04-23) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 02682d0b86..c203cc6d94 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-22" + #define STRING_DISTRIBUTION_DATE "2020-04-23" #endif /** From 2f6262c27b11598293839f6d46f3b340ee6a1f4c Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Thu, 23 Apr 2020 04:03:28 +0200 Subject: [PATCH 0243/1454] Automatic Tool Migration feature (#17248) --- Marlin/Configuration_adv.h | 56 ++- Marlin/src/feature/runout.cpp | 9 + Marlin/src/gcode/config/M217.cpp | 112 ++++-- Marlin/src/gcode/config/M221.cpp | 6 +- Marlin/src/gcode/sd/M1001.cpp | 5 +- Marlin/src/inc/Conditionals_post.h | 4 +- Marlin/src/inc/SanityCheck.h | 13 +- Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 3 +- Marlin/src/lcd/extui/ui_api.cpp | 5 +- Marlin/src/lcd/language/language_cz.h | 4 +- Marlin/src/lcd/language/language_de.h | 6 +- Marlin/src/lcd/language/language_en.h | 15 +- Marlin/src/lcd/language/language_es.h | 4 +- Marlin/src/lcd/language/language_fr.h | 17 +- Marlin/src/lcd/language/language_gl.h | 4 +- Marlin/src/lcd/language/language_it.h | 4 +- Marlin/src/lcd/language/language_pl.h | 4 +- Marlin/src/lcd/language/language_pt_br.h | 4 +- Marlin/src/lcd/language/language_tr.h | 4 +- Marlin/src/lcd/language/language_vi.h | 4 +- Marlin/src/lcd/language/language_zh_TW.h | 4 +- Marlin/src/lcd/menu/menu_configuration.cpp | 49 ++- Marlin/src/module/configuration_store.cpp | 24 +- Marlin/src/module/planner.h | 12 +- Marlin/src/module/tool_change.cpp | 323 +++++++++++++++--- Marlin/src/module/tool_change.h | 30 +- buildroot/share/tests/BIGTREE_GTR_V1_0-tests | 1 + 27 files changed, 575 insertions(+), 151 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index cc28c050a6..75c86931c7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1847,19 +1847,55 @@ */ #if EXTRUDERS > 1 // Z raise distance for tool-change, as needed for some extruders - #define TOOLCHANGE_ZRAISE 2 // (mm) - //#define TOOLCHANGE_NO_RETURN // Never return to the previous position on tool-change + #define TOOLCHANGE_ZRAISE 2 // (mm) + //#define TOOLCHANGE_ZRAISE_BEFORE_RETRACT // Apply raise before swap retraction (if enabled) + //#define TOOLCHANGE_NO_RETURN // Never return to previous position on tool-change #if ENABLED(TOOLCHANGE_NO_RETURN) - //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // G-code to run after tool-change is complete + //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change #endif - // Retract and prime filament on tool-change + /** + * Retract and prime filament on tool-change to reduce + * ooze and stringing and to get cleaner transitions. + */ //#define TOOLCHANGE_FILAMENT_SWAP #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - #define TOOLCHANGE_FIL_SWAP_LENGTH 12 // (mm) - #define TOOLCHANGE_FIL_EXTRA_PRIME 2 // (mm) - #define TOOLCHANGE_FIL_SWAP_RETRACT_SPEED 3600 // (mm/m) - #define TOOLCHANGE_FIL_SWAP_PRIME_SPEED 3600 // (mm/m) + // Load / Unload + #define TOOLCHANGE_FS_LENGTH 12 // (mm) Load / Unload length + #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart, fine tune by LCD/Gcode) + #define TOOLCHANGE_FS_RETRACT_SPEED (50*60) // (mm/m) (Unloading) + #define TOOLCHANGE_FS_UNRETRACT_SPEED (25*60) // (mm/m) (On SINGLENOZZLE or Bowden loading must be slowed down) + + // Longer prime to clean out a SINGLENOZZLE + #define TOOLCHANGE_FS_EXTRA_PRIME 0 // (mm) Extra priming length + #define TOOLCHANGE_FS_PRIME_SPEED (4.6*60) // (mm/m) Extra priming feedrate + #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm/m) Retract before cooling for less stringing, better wipe, etc. + + // Cool after prime to reduce stringing + #define TOOLCHANGE_FS_FAN -1 // Fan index or -1 to skip + #define TOOLCHANGE_FS_FAN_SPEED 255 // 0-255 + #define TOOLCHANGE_FS_FAN_TIME 10 // (seconds) + + // Swap uninitialized extruder with TOOLCHANGE_FS_PRIME_SPEED for all lengths (recover + prime) + // (May break filament if not retracted beforehand.) + //#define TOOLCHANGE_FS_INIT_BEFORE_SWAP + + // Prime on the first T command even if the same or no toolchange / swap + // Enable it (M217 V[0/1]) before printing, to avoid unwanted priming on host connect + //#define TOOLCHANGE_FS_PRIME_FIRST_USED + + /** + * Tool Change Migration + * This feature provides G-code and LCD options to switch tools mid-print. + * All applicable tool properties are migrated so the print can continue. + * Tools must be closely matching and other restrictions may apply. + * Useful to: + * - Change filament color without interruption + * - Switch spools automatically on filament runout + * - Switch to a different nozzle on an extruder jam + */ + #define TOOLCHANGE_MIGRATION_FEATURE + #endif /** @@ -1870,8 +1906,10 @@ #if ENABLED(TOOLCHANGE_PARK) #define TOOLCHANGE_PARK_XY { X_MIN_POS + 10, Y_MIN_POS + 10 } #define TOOLCHANGE_PARK_XY_FEEDRATE 6000 // (mm/m) + //#define TOOLCHANGE_PARK_X_ONLY // X axis only move + //#define TOOLCHANGE_PARK_Y_ONLY // Y axis only move #endif -#endif +#endif // EXTRUDERS > 1 /** * Advanced Pause diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index f74e0c741b..bba4f4b1fa 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -39,6 +39,10 @@ bool FilamentMonitorBase::enabled = true, bool FilamentMonitorBase::host_handling; // = false #endif +#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + #include "../module/tool_change.h" +#endif + /** * Called by FilamentSensorSwitch::run when filament is detected. * Called by FilamentSensorEncoder::block_completed when motion is detected. @@ -76,6 +80,11 @@ void event_filament_runout() { if (TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) return; // Action already in progress. Purge triggered repeated runout. + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + if (migration.in_progress) return; // Action already in progress. Purge triggered repeated runout. + if (migration.automode) { extruder_migration(); return; } + #endif + TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getActiveTool())); #if EITHER(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS) diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 44e69c4298..6e8c899fb0 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -27,6 +27,10 @@ #include "../gcode.h" #include "../../module/tool_change.h" +#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + #include "../../module/motion.h" +#endif + #include "../../MarlinCore.h" // for SP_X_STR, etc. extern const char SP_X_STR[], SP_Y_STR[], SP_Z_STR[]; @@ -35,16 +39,30 @@ void M217_report(const bool eeprom=false) { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Toolchange:")); - SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length)); - SERIAL_ECHOPAIR_P(SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime)); - SERIAL_ECHOPAIR_P(SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); - SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed)); + SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length), + " B", LINEAR_UNIT(toolchange_settings.extra_resume)); + SERIAL_ECHOPAIR_P(SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), + SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); + SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed), + " U", LINEAR_UNIT(toolchange_settings.unretract_speed), + " F", toolchange_settings.fan_speed, + " G", toolchange_settings.fan_time); + + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + SERIAL_ECHOPAIR(" N", int(migration.automode)); + SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last)); + #endif #if ENABLED(TOOLCHANGE_PARK) + SERIAL_ECHOPAIR(" W", LINEAR_UNIT(toolchange_settings.enable_park)); SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)); SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)); #endif + #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) + SERIAL_ECHOPAIR(" V", LINEAR_UNIT(enable_first_prime)); + #endif + #else UNUSED(eeprom); @@ -58,48 +76,98 @@ void M217_report(const bool eeprom=false) { /** * M217 - Set SINGLENOZZLE toolchange parameters * + * // Tool change command + * Q Prime active tool and exit + * + * // Tool change settings * S[linear] Swap length - * E[linear] Purge length + * B[linear] Extra Swap length + * E[linear] Prime length * P[linear/m] Prime speed * R[linear/m] Retract speed + * U[linear/m] UnRetract speed + * V[linear] 0/1 Enable auto prime first extruder used + * W[linear] 0/1 Enable park & Z Raise * X[linear] Park X (Requires TOOLCHANGE_PARK) * Y[linear] Park Y (Requires TOOLCHANGE_PARK) * Z[linear] Z Raise + * F[linear] Fan Speed 0-255 + * G[linear/s] Fan time + * + * Tool migration settings + * A[0|1] Enable auto-migration on runout + * L[index] Last extruder to use for auto-migration + * + * Tool migration command + * T[index] Migrate to next extruder or the given extruder */ void GcodeSuite::M217() { - #define SPR_PARAM - #define XY_PARAM - #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - #undef SPR_PARAM - #define SPR_PARAM "SPRE" + static constexpr float max_extrude = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 500); - static constexpr float max_extrude = - #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - EXTRUDE_MAXLENGTH - #else - 500 - #endif - ; + if (parser.seen('Q')) { tool_change_prime(); return; } if (parser.seenval('S')) { const float v = parser.value_linear_units(); toolchange_settings.swap_length = constrain(v, 0, max_extrude); } + if (parser.seenval('B')) { const float v = parser.value_linear_units(); toolchange_settings.extra_resume = constrain(v, -10, 10); } if (parser.seenval('E')) { const float v = parser.value_linear_units(); toolchange_settings.extra_prime = constrain(v, 0, max_extrude); } if (parser.seenval('P')) { const int16_t v = parser.value_linear_units(); toolchange_settings.prime_speed = constrain(v, 10, 5400); } if (parser.seenval('R')) { const int16_t v = parser.value_linear_units(); toolchange_settings.retract_speed = constrain(v, 10, 5400); } + if (parser.seenval('U')) { const int16_t v = parser.value_linear_units(); toolchange_settings.unretract_speed = constrain(v, 10, 5400); } + #if TOOLCHANGE_FS_FAN >= 0 && FAN_COUNT > 0 + if (parser.seenval('F')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_speed = constrain(v, 0, 255); } + if (parser.seenval('G')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_time = constrain(v, 1, 30); } + #endif + #endif + + #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) + if (parser.seenval('V')) { enable_first_prime = parser.value_linear_units(); } #endif #if ENABLED(TOOLCHANGE_PARK) - #undef XY_PARAM - #define XY_PARAM "XY" - if (parser.seenval('X')) { toolchange_settings.change_point.x = parser.value_linear_units(); } - if (parser.seenval('Y')) { toolchange_settings.change_point.y = parser.value_linear_units(); } + if (parser.seenval('W')) { toolchange_settings.enable_park = parser.value_linear_units(); } + if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); } + if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); } #endif if (parser.seenval('Z')) { toolchange_settings.z_raise = parser.value_linear_units(); } - if (!parser.seen(SPR_PARAM XY_PARAM "Z")) M217_report(); + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + migration.target = 0; // 0 = disabled + + if (parser.seenval('L')) { // Last + const int16_t lval = parser.value_int(); + if (WITHIN(lval, 0, EXTRUDERS - 1)) { + migration.last = lval; + migration.automode = (active_extruder < migration.last); + } + } + + if (parser.seen('A')) // Auto on/off + migration.automode = parser.value_bool(); + + if (parser.seen('T')) { // Migrate now + if (parser.has_value()) { + const int16_t tval = parser.value_int(); + if (WITHIN(tval, 0, EXTRUDERS - 1) && tval != active_extruder) { + migration.target = tval + 1; + extruder_migration(); + migration.target = 0; // disable + return; + } + else + migration.target = 0; // disable + } + else { + extruder_migration(); + return; + } + } + + #endif + + M217_report(); } #endif // EXTRUDERS > 1 diff --git a/Marlin/src/gcode/config/M221.cpp b/Marlin/src/gcode/config/M221.cpp index 8522b544fc..7f170e012b 100644 --- a/Marlin/src/gcode/config/M221.cpp +++ b/Marlin/src/gcode/config/M221.cpp @@ -33,10 +33,8 @@ void GcodeSuite::M221() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - if (parser.seenval('S')) { - planner.flow_percentage[target_extruder] = parser.value_int(); - planner.refresh_e_factor(target_extruder); - } + if (parser.seenval('S')) + planner.set_flow(target_extruder, parser.value_int()); else { SERIAL_ECHO_START(); SERIAL_CHAR('E', '0' + target_extruder); diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index e5082be31f..8f1427a9ab 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -31,10 +31,6 @@ #include "../queue.h" #endif -#if HAS_LEDS_OFF_FLAG - #include "../../MarlinCore.h" -#endif - #if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) #include "../../lcd/ultralcd.h" #endif @@ -44,6 +40,7 @@ #endif #if HAS_LEDS_OFF_FLAG + #include "../../MarlinCore.h" // for wait_for_user_response #include "../../feature/leds/printer_event_leds.h" #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index bb42c39665..9269c76b7d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2222,8 +2222,8 @@ #define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 #endif -#if EXTRUDERS > 1 && !defined(TOOLCHANGE_FIL_EXTRA_PRIME) - #define TOOLCHANGE_FIL_EXTRA_PRIME 0 +#if EXTRUDERS > 1 && !defined(TOOLCHANGE_FS_EXTRA_PRIME) + #define TOOLCHANGE_FS_EXTRA_PRIME 0 #endif /** diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 6a0d0bd8e6..d1024e44ce 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -833,14 +833,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - #ifndef TOOLCHANGE_FIL_SWAP_LENGTH - #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FIL_SWAP_LENGTH. Please update your Configuration." - #elif !defined(TOOLCHANGE_FIL_SWAP_RETRACT_SPEED) - #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FIL_SWAP_RETRACT_SPEED. Please update your Configuration." - #elif !defined(TOOLCHANGE_FIL_SWAP_PRIME_SPEED) - #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FIL_SWAP_PRIME_SPEED. Please update your Configuration." + #ifndef TOOLCHANGE_FS_LENGTH + #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_LENGTH. Please update your Configuration_adv.h." + #elif !defined(TOOLCHANGE_FS_RETRACT_SPEED) + #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_RETRACT_SPEED. Please update your Configuration_adv.h." + #elif !defined(TOOLCHANGE_FS_PRIME_SPEED) + #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_PRIME_SPEED. Please update your Configuration_adv.h." #endif #endif + #if ENABLED(TOOLCHANGE_PARK) #ifndef TOOLCHANGE_PARK_XY #error "TOOLCHANGE_PARK requires TOOLCHANGE_PARK_XY. Please update your Configuration." diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index 8bbbb231e2..91acd0a360 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -573,8 +573,7 @@ void DGUSScreenVariableHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, voi #endif } - planner.flow_percentage[target_extruder] = newvalue; - planner.refresh_e_factor(target_extruder); + planner.set_flow(target_extruder, newvalue); ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel #else UNUSED(var); UNUSED(val_ptr); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index b272d9d496..dd5ddd3b66 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -669,10 +669,7 @@ namespace ExtUI { float getRetractAcceleration_mm_s2() { return planner.settings.retract_acceleration; } float getTravelAcceleration_mm_s2() { return planner.settings.travel_acceleration; } void setFeedrate_mm_s(const feedRate_t fr) { feedrate_mm_s = fr; } - void setFlow_percent(const int16_t flow, const extruder_t extr) { - planner.flow_percentage[extr] = flow; - planner.refresh_e_factor(extr); - } + void setFlow_percent(const int16_t flow, const extruder_t extr) { planner.set_flow(extr, flow); } void setMinFeedrate_mm_s(const feedRate_t fr) { planner.settings.min_feedrate_mm_s = fr; } void setMinTravelFeedrate_mm_s(const feedRate_t fr) { planner.settings.min_travel_feedrate_mm_s = fr; } void setPrintingAcceleration_mm_s2(const float acc) { planner.settings.acceleration = acc; } diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index c8f0e6b13b..3e85224988 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -357,8 +357,8 @@ namespace Language_cz { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Délka zavedení"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Výměna nástroje"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Zdvih Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Rychlost primár."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Rychlost retrak."); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Rychlost primár."); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Rychlost retrak."); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Tryska standby"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Vyměnit filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Vyměnit filament *"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 4d0516e8d6..211869fc9c 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -347,9 +347,9 @@ namespace Language_de { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Entladelänge"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Werkzeugwechsel"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z anheben"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prime-Geschwin."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Einzug-Geschwin."); - + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime-Geschwin."); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Einzug-Geschwin."); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düsen-Standby"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Filament wechseln"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Filament wechseln *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Filament laden"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index a3e25d9145..94d9d44cf7 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -371,11 +371,22 @@ namespace Language_en { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoRetr."); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Swap Length"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purge Length"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Tool Change"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Raise"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prime Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Retract Speed"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime Speed"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Retract Speed"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Change Filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Change Filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Load Filament"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 015663e885..c95fd09f10 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -367,8 +367,8 @@ namespace Language_es { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purgar longitud"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Herramienta"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Aumentar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Vel. de Cebado"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Vel. de retracción"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Vel. de Cebado"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de retracción"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar filamento *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar filamento"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 2fca6adbb4..23258b9015 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -53,7 +53,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Config. avancée"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuration"); - PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Exéc. auto#.gcode"); + PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Exéc. auto.gcode"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Arrêter moteurs"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barre progress."); @@ -329,10 +329,21 @@ namespace Language_fr { PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Rétraction auto"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Changement outil"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Augmenter Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Vitesse primaire"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Vitesse rétract°"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Vitesse primaire"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vitesse rétract°"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Garer Extrudeur"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Vitesse reprise"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Vit. ventil."); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Temps ventil."); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Migration d'outil"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Migration auto"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Extrudeur Final"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrer vers *"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Attente buse"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Longueur retrait"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Longueur Extra"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Longueur de purge"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Changer filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Changer filament *"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index fa9f371971..d747b78183 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -371,8 +371,8 @@ namespace Language_gl { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lonxitude de Purga"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Ferramenta"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Velocidade prim."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Vel. de Retracción"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocidade prim."); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de Retracción"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar Filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar Filamento *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar Filamento"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index d17c100490..20af26be07 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -370,8 +370,8 @@ namespace Language_it { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lunghezza spurgo"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambio utensile"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Risalita Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Velocità innesco"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Velocità retrazione"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocità innesco"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Velocità retrazione"); PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Ugello Parcheggiato"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Standby ugello"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 0cb4f25499..4fb2df6eec 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -339,8 +339,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prędkość napełniania"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Prędkość wycofania"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 469b75e823..0d355147f8 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -286,8 +286,8 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Distancia Retração"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Mudar Ferramenta"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Preparar Veloc."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Veloc. Retração"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Preparar Veloc."); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Veloc. Retração"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Trocar Filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Trocar Filamento *"); PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Carregar Filamento *"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index a33b0d315d..aa68ece992 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -365,8 +365,8 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tasfiye uzunluğu"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Takım Değişimi"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Yükselt"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Birincil Hız"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Geri Çekme Hızı"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Birincil Hız"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Geri Çekme Hızı"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozul Beklemede"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Filaman Değiştir"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Filaman Değiştir *"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 781a1242b8..8538c81831 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -299,8 +299,8 @@ namespace Language_vi { PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Khoảng Cách Rút"); // Retract Distance PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Thay Đổi Công Cụ"); // Tool Change PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Đưa Lên Z"); // Z Raise - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Tốc Độ Tuôn Ra"); // Prime Speed - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Tốc Độ Rút Lại"); // Retract Speed + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Tốc Độ Tuôn Ra"); // Prime Speed + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Tốc Độ Rút Lại"); // Retract Speed PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Thay dây nhựa"); // change filament PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Thay dây nhựa *"); // change filament PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Nạp dây nhựa"); // load filament diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 6bb7d759f6..1019fcb03a 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -346,8 +346,8 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("清除長度"); //"Purge Length" PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("交換工具"); //"Tool Change" PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z軸提昇"); //"Z Raise" - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("最高速度"); //"Prime Speed" - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("收回速度"); //"Retract Speed" + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("最高速度"); //"Prime Speed" + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("收回速度"); //"Retract Speed" PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("噴嘴待機"); //"Nozzle Standby" PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("更換絲料"); //"Change filament" PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("更換絲料 *"); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index b0202198b7..bf7be4dbc2 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -104,22 +104,50 @@ void menu_advanced_settings(); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - static constexpr float max_extrude = - #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - EXTRUDE_MAXLENGTH - #else - 500 - #endif - ; + static constexpr float max_extrude = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 500); + #if ENABLED(TOOLCHANGE_PARK) + EDIT_ITEM(bool, MSG_FILAMENT_PARK_ENABLED, &toolchange_settings.enable_park); + #endif EDIT_ITEM(float3, MSG_FILAMENT_SWAP_LENGTH, &toolchange_settings.swap_length, 0, max_extrude); + EDIT_ITEM(float41sign, MSG_FILAMENT_SWAP_EXTRA, &toolchange_settings.extra_resume, -10, 10); + EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_RETRACT_SPEED, &toolchange_settings.retract_speed, 10, 5400); + EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_UNRETRACT_SPEED, &toolchange_settings.unretract_speed, 10, 5400); EDIT_ITEM(float3, MSG_FILAMENT_PURGE_LENGTH, &toolchange_settings.extra_prime, 0, max_extrude); - EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_RETRACT_SPD, &toolchange_settings.retract_speed, 10, 5400); - EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_PRIME_SPD, &toolchange_settings.prime_speed, 10, 5400); + EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_PRIME_SPEED, &toolchange_settings.prime_speed, 10, 5400); + EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_FAN_SPEED, &toolchange_settings.fan_speed, 0, 255); + EDIT_ITEM_FAST(int4, MSG_SINGLENOZZLE_FAN_TIME, &toolchange_settings.fan_time, 1, 30); #endif EDIT_ITEM(float3, MSG_TOOL_CHANGE_ZLIFT, &toolchange_settings.z_raise, 0, 10); END_MENU(); } + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + + #include "../../module/motion.h" // for active_extruder + + void menu_toolchange_migration() { + START_MENU(); + BACK_ITEM(MSG_CONFIGURATION); + + // Auto mode ON/OFF + EDIT_ITEM(bool, MSG_TOOL_MIGRATION_AUTO, &migration.automode); + EDIT_ITEM(uint8, MSG_TOOL_MIGRATION_END, &migration.last, 0, EXTRUDERS - 1); + + // Migrate to a chosen extruder + PGM_P const msg_migrate = GET_TEXT(MSG_TOOL_MIGRATION_SWAP); + LOOP_L_N(s, EXTRUDERS) { + if (s != active_extruder) { + ACTION_ITEM_N_P(s, msg_migrate, []{ + char cmd[12]; + sprintf_P(cmd, PSTR("M217 T%i"), int(MenuItemBase::itemIndex)); + queue.inject(cmd); + }); + } + } + END_MENU(); + } + #endif + #endif #if HAS_HOTEND_OFFSET @@ -373,6 +401,9 @@ void menu_configuration() { // #if EXTRUDERS > 1 SUBMENU(MSG_TOOL_CHANGE, menu_tool_change); + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + SUBMENU(MSG_TOOL_MIGRATION, menu_toolchange_migration); + #endif #endif // diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 698447a4be..84b8c75370 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -2423,16 +2423,32 @@ void MarlinSettings::reset() { #if EXTRUDERS > 1 #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - toolchange_settings.swap_length = TOOLCHANGE_FIL_SWAP_LENGTH; - toolchange_settings.extra_prime = TOOLCHANGE_FIL_EXTRA_PRIME; - toolchange_settings.prime_speed = TOOLCHANGE_FIL_SWAP_PRIME_SPEED; - toolchange_settings.retract_speed = TOOLCHANGE_FIL_SWAP_RETRACT_SPEED; + toolchange_settings.swap_length = TOOLCHANGE_FS_LENGTH; + toolchange_settings.extra_resume = TOOLCHANGE_FS_EXTRA_RESUME_LENGTH; + toolchange_settings.retract_speed = TOOLCHANGE_FS_RETRACT_SPEED; + toolchange_settings.unretract_speed = TOOLCHANGE_FS_UNRETRACT_SPEED; + toolchange_settings.extra_prime = TOOLCHANGE_FS_EXTRA_PRIME; + toolchange_settings.prime_speed = TOOLCHANGE_FS_PRIME_SPEED; + toolchange_settings.fan_speed = TOOLCHANGE_FS_FAN_SPEED; + toolchange_settings.fan_time = TOOLCHANGE_FS_FAN_TIME; #endif + + #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) + enable_first_prime = false; + #endif + #if ENABLED(TOOLCHANGE_PARK) constexpr xyz_pos_t tpxy = TOOLCHANGE_PARK_XY; + toolchange_settings.enable_park = true; toolchange_settings.change_point = tpxy; #endif + toolchange_settings.z_raise = TOOLCHANGE_ZRAISE; + + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + migration = migration_defaults; + #endif + #endif #if ENABLED(BACKLASH_GCODE) diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 7ac7d5ade7..87a6e7c0a8 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -423,12 +423,14 @@ class Planner { #if EXTRUDERS FORCE_INLINE static void refresh_e_factor(const uint8_t e) { - e_factor[e] = (flow_percentage[e] * 0.01f - #if DISABLED(NO_VOLUMETRICS) - * volumetric_multiplier[e] - #endif - ); + e_factor[e] = flow_percentage[e] * 0.01f * TERN(NO_VOLUMETRICS, 1.0f, volumetric_multiplier[e]); } + + static inline void set_flow(const uint8_t e, const int16_t flow) { + flow_percentage[e] = flow; + refresh_e_factor(e); + } + #endif // Manage fans, paste pressure, etc. diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 23925d630c..210d220e7b 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -38,6 +38,15 @@ toolchange_settings_t toolchange_settings; // Initialized by settings.load() #endif +#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + migration_settings_t migration = migration_defaults; + bool enable_first_prime; +#endif + +#if ENABLED(TOOLCHANGE_FS_INIT_BEFORE_SWAP) + bool toolchange_extruder_ready[EXTRUDERS]; +#endif + #if ENABLED(SINGLENOZZLE) uint16_t singlenozzle_temp[EXTRUDERS]; #if FAN_COUNT > 0 @@ -85,6 +94,14 @@ #include "../feature/pause.h" #endif +#if ENABLED(TOOLCHANGE_FILAMENT_SWAP) + #include "../gcode/gcode.h" + #if TOOLCHANGE_FS_WIPE_RETRACT <= 0 + #undef TOOLCHANGE_FS_WIPE_RETRACT + #define TOOLCHANGE_FS_WIPE_RETRACT 0 + #endif +#endif + #if DO_SWITCH_EXTRUDER #if EXTRUDERS > 3 @@ -759,6 +776,77 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #endif // DUAL_X_CARRIAGE +/** + * Prime active tool using TOOLCHANGE_FILAMENT_SWAP settings + */ +#if ENABLED(TOOLCHANGE_FILAMENT_SWAP) + +void tool_change_prime() { + if (toolchange_settings.extra_prime > 0 + && TERN(PREVENT_COLD_EXTRUSION, !thermalManager.targetTooColdToExtrude(active_extruder), 1) + ) { + destination = current_position; // Remember the old position + + const bool ok = TERN1(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); + + // Z raise + if (ok) { + // Do a small lift to avoid the workpiece in the move back (below) + current_position.z += toolchange_settings.z_raise; + #if HAS_SOFTWARE_ENDSTOPS + NOMORE(current_position.z, soft_endstop.max.z); + #endif + fast_line_to_current(Z_AXIS); + planner.synchronize(); + } + + // Park + #if ENABLED(TOOLCHANGE_PARK) + if (ok) { + TERN(TOOLCHANGE_PARK_Y_ONLY,,current_position.x = toolchange_settings.change_point.x); + TERN(TOOLCHANGE_PARK_X_ONLY,,current_position.y = toolchange_settings.change_point.y); + planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), active_extruder); + planner.synchronize(); + } + #endif + + // Prime (All distances are added and slowed down to ensure secure priming in all circumstances) + unscaled_e_move(toolchange_settings.swap_length + toolchange_settings.extra_prime, MMM_TO_MMS(toolchange_settings.prime_speed)); + + // Cutting retraction + #if TOOLCHANGE_FS_WIPE_RETRACT + unscaled_e_move(-(TOOLCHANGE_FS_WIPE_RETRACT), MMM_TO_MMS(toolchange_settings.retract_speed)); + #endif + + // Cool down with fan + #if TOOLCHANGE_FS_FAN >= 0 && FAN_COUNT > 0 + const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; + safe_delay(toolchange_settings.fan_time * 1000); + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = fansp; + #endif + + // Move back + #if ENABLED(TOOLCHANGE_PARK) + if (ok) { + #if ENABLED(TOOLCHANGE_NO_RETURN) + do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); + #else + do_blocking_move_to(destination, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE)); + #endif + } + #endif + + // Cutting recover + unscaled_e_move(toolchange_settings.extra_resume + TOOLCHANGE_FS_WIPE_RETRACT, MMM_TO_MMS(toolchange_settings.unretract_speed)); + + planner.synchronize(); + current_position.e = destination.e; + sync_plan_position_e(); // Resume at the old E position + } +} +#endif + /** * Perform a tool-change, which may result in moving the * previous tool out of the way and the new tool into place. @@ -826,39 +914,52 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { const uint8_t old_tool = active_extruder; const bool can_move_away = !no_move && !idex_full_control; - #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - const bool should_swap = can_move_away && toolchange_settings.swap_length; - #if ENABLED(PREVENT_COLD_EXTRUSION) - const bool too_cold = !DEBUGGING(DRYRUN) && (thermalManager.targetTooColdToExtrude(old_tool) || thermalManager.targetTooColdToExtrude(new_tool)); - #else - constexpr bool too_cold = false; - #endif - if (should_swap) { - if (too_cold) { - SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); - #if ENABLED(SINGLENOZZLE) - active_extruder = new_tool; - return; - #endif - } - else { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); - #else - current_position.e -= toolchange_settings.swap_length / planner.e_factor[old_tool]; - planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.retract_speed), old_tool); - planner.synchronize(); - #endif - } - } - #endif // TOOLCHANGE_FILAMENT_SWAP - #if HAS_LEVELING && DISABLED(SINGLENOZZLE) // Set current position to the physical position TEMPORARY_BED_LEVELING_STATE(false); #endif + // First tool priming. To prime again, reboot the machine. + #if BOTH(TOOLCHANGE_FILAMENT_SWAP, TOOLCHANGE_FS_PRIME_FIRST_USED) + static bool first_tool_is_primed = false; + if (new_tool == old_tool && !first_tool_is_primed && enable_first_prime) { + tool_change_prime(); + first_tool_is_primed = true; + toolchange_extruder_ready[old_tool] = true; // Primed and initialized + } + #endif + if (new_tool != old_tool) { + destination = current_position; + + // Z raise before retraction + #if ENABLED(TOOLCHANGE_ZRAISE_BEFORE_RETRACT) && DISABLED(SWITCHING_NOZZLE) + if (can_move_away && TERN1(toolchange_settings.enable_park)) { + // Do a small lift to avoid the workpiece in the move back (below) + current_position.z += toolchange_settings.z_raise; + #if HAS_SOFTWARE_ENDSTOPS + NOMORE(current_position.z, soft_endstop.max.z); + #endif + fast_line_to_current(Z_AXIS); + planner.synchronize(); + } + #endif + + // Unload / Retract + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) + const bool should_swap = can_move_away && toolchange_settings.swap_length; + too_cold = TERN0(PREVENT_COLD_EXTRUSION, + !DEBUGGING(DRYRUN) && (thermalManager.targetTooColdToExtrude(old_tool) || thermalManager.targetTooColdToExtrude(new_tool)) + ); + if (should_swap) { + if (too_cold) { + SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); + if (ENABLED(SINGLENOZZLE)) { active_extruder = new_tool; return; } + } + else + unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); + } + #endif TERN_(SWITCHING_NOZZLE_TWO_SERVOS, raise_nozzle(old_tool)); @@ -877,18 +978,23 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #endif - destination = current_position; - - #if DISABLED(SWITCHING_NOZZLE) - if (can_move_away) { + #if DISABLED(TOOLCHANGE_ZRAISE_BEFORE_RETRACT) && DISABLED(SWITCHING_NOZZLE) + if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; #if HAS_SOFTWARE_ENDSTOPS NOMORE(current_position.z, soft_endstop.max.z); #endif fast_line_to_current(Z_AXIS); - TERN_(TOOLCHANGE_PARK, current_position = toolchange_settings.change_point); - planner.buffer_line(current_position, feedrate_mm_s, old_tool); + } + #endif + + // Toolchange park + #if ENABLED(TOOLCHANGE_PARK) && DISABLED(SWITCHING_NOZZLE) + if (can_move_away && toolchange_settings.enable_park) { + TERN(TOOLCHANGE_PARK_Y_ONLY,,current_position.x = toolchange_settings.change_point.x); + TERN(TOOLCHANGE_PARK_X_ONLY,,current_position.y = toolchange_settings.change_point.y); + planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), old_tool); planner.synchronize(); } #endif @@ -932,9 +1038,8 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { move_nozzle_servo(new_tool); #endif - #if DISABLED(DUAL_X_CARRIAGE) - active_extruder = new_tool; // Set the new active extruder - #endif + // Set the new active extruder + if (DISABLED(DUAL_X_CARRIAGE)) active_extruder = new_tool; // The newly-selected extruder XYZ is actually at... if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Offset Tool XYZ by { ", diff.x, ", ", diff.y, ", ", diff.z, " }"); @@ -951,7 +1056,8 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // Return to position and lower again - if (safe_to_move && !no_move && IsRunning()) { + const bool should_move = safe_to_move && !no_move && IsRunning(); + if (should_move) { #if ENABLED(SINGLENOZZLE) #if FAN_COUNT > 0 @@ -969,17 +1075,35 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) if (should_swap && !too_cold) { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - unscaled_e_move(toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.prime_speed)); - unscaled_e_move(toolchange_settings.extra_prime, ADVANCED_PAUSE_PURGE_FEEDRATE); - #else - current_position.e += toolchange_settings.swap_length / planner.e_factor[new_tool]; - planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed), new_tool); - current_position.e += toolchange_settings.extra_prime / planner.e_factor[new_tool]; - planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed * 0.2f), new_tool); + + float fr = toolchange_settings.unretract_speed; + + #if ENABLED(TOOLCHANGE_FS_INIT_BEFORE_SWAP) + if (!toolchange_extruder_ready[new_tool]) { + toolchange_extruder_ready[new_tool] = true; + fr = toolchange_settings.prime_speed; // Next move is a prime + unscaled_e_move(0, MMM_TO_MMS(fr)); // Init planner with 0 length move + } + #endif + + // Unretract (or Prime) + unscaled_e_move(toolchange_settings.swap_length, MMM_TO_MMS(fr)); + + // Extra Prime + unscaled_e_move(toolchange_settings.extra_prime, MMM_TO_MMS(toolchange_settings.prime_speed)); + + // Cutting retraction + #if TOOLCHANGE_FS_WIPE_RETRACT + unscaled_e_move(-(TOOLCHANGE_FS_WIPE_RETRACT), MMM_TO_MMS(toolchange_settings.retract_speed)); + #endif + + // Cool down with fan + #if TOOLCHANGE_FS_FAN >= 0 && FAN_COUNT > 0 + const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; + safe_delay(toolchange_settings.fan_time * 1000); + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = fansp; #endif - planner.synchronize(); - planner.set_e_position_mm((destination.e = current_position.e = current_position.e - (TOOLCHANGE_FIL_EXTRA_PRIME))); } #endif @@ -1000,22 +1124,43 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(TOOLCHANGE_NO_RETURN) // Just move back down if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move back Z only"); + + #if ENABLED(TOOLCHANGE_PARK) + if (toolchange_settings.enable_park) + #endif do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); + #else // Move back to the original (or adjusted) position if (DEBUGGING(LEVELING)) DEBUG_POS("Move back", destination); - do_blocking_move_to(destination); + + #if ENABLED(TOOLCHANGE_PARK) + if (toolchange_settings.enable_park) do_blocking_move_to_xy_z(destination, destination.z, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE)); + #else + do_blocking_move_to_xy(destination); + #endif + #endif } + else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move back skipped"); + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) + if (should_swap && !too_cold) { + // Cutting recover + unscaled_e_move(toolchange_settings.extra_resume + TOOLCHANGE_FS_WIPE_RETRACT, MMM_TO_MMS(toolchange_settings.unretract_speed)); + current_position.e = 0; + sync_plan_position_e(); // New extruder primed and set to 0 + } + #endif + TERN_(DUAL_X_CARRIAGE, active_extruder_parked = false); } + #if ENABLED(SWITCHING_NOZZLE) - else { - // Move back down. (Including when the new tool is higher.) + // Move back down. (Including when the new tool is higher.) + if (!should_move) do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); - } #endif TERN_(PRUSA_MMU2, mmu2.tool_change(new_tool)); @@ -1053,3 +1198,79 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // EXTRUDERS > 1 } + +#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + + void extruder_migration() { + + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (thermalManager.targetTooColdToExtrude(active_extruder)) return; + #endif + + // No auto-migration or specified target? + if (!migration.target && active_extruder >= migration.last) { + migration.automode = false; + return; + } + + // Migrate to a target or the next extruder + + uint8_t migration_extruder = active_extruder; + + if (migration.target) { + // Specified target ok? + const int16_t t = migration.target - 1; + if (t != active_extruder) migration_extruder = t; + } + else if (migration.automode && migration_extruder < migration.last && migration_extruder < EXTRUDERS - 1) + migration_extruder++; + + if (migration_extruder == active_extruder) return; + + // Migration begins + + migration.in_progress = true; // Prevent runout script + planner.synchronize(); + + // Remember position before migration + const float resume_current_e = current_position.e; + + // Migrate the flow + planner.set_flow(migration_extruder, planner.flow_percentage[active_extruder]); + + // Migrate the retracted state + #if ENABLED(FWRETRACT) + fwretract.retracted[migration_extruder] = fwretract.retracted[active_extruder]; + #endif + + // Migrate the temperature to the new hotend + #if HOTENDS > 1 + thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); + #if HAS_DISPLAY + thermalManager.set_heating_message(0); + #endif + thermalManager.wait_for_hotend(active_extruder); + #endif + + // Perform the tool change + tool_change(migration_extruder); + + // Retract if previously retracted + #if ENABLED(FWRETRACT) + if (fwretract.retracted[active_extruder]) + unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); + #endif + + // If no available extruder + if (EXTRUDERS < 2 || active_extruder >= EXTRUDERS - 2 || active_extruder == migration.last) + migration.automode = false; + + migration.in_progress = false; + + current_position.e = resume_current_e; + + planner.synchronize(); + planner.set_e_position_mm(current_position.e); // New extruder primed and ready + } + +#endif // TOOLCHANGE_MIGRATION_FEATURE diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 0e915a0415..534a17e946 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -28,15 +28,39 @@ typedef struct { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - float swap_length, extra_prime; - int16_t prime_speed, retract_speed; + float swap_length, extra_prime, extra_resume; + int16_t prime_speed, retract_speed, unretract_speed, fan, fan_speed, fan_time; + #endif + #if ENABLED(TOOLCHANGE_PARK) + bool enable_park; + xy_pos_t change_point; #endif - TERN_(TOOLCHANGE_PARK, xy_pos_t change_point); float z_raise; } toolchange_settings_t; extern toolchange_settings_t toolchange_settings; + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) + extern void tool_change_prime(); + #endif + + #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) + extern bool enable_first_prime; + #endif + + #if ENABLED(TOOLCHANGE_FS_INIT_BEFORE_SWAP) + extern bool toolchange_extruder_ready[EXTRUDERS]; + #endif + + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + typedef struct { + uint8_t target, last; + bool automode, in_progress; + } migration_settings_t; + constexpr migration_settings_t migration_defaults = { 0, 0, false, false }; + extern migration_settings_t migration; + void extruder_migration(); + #endif #endif #if DO_SWITCH_EXTRUDER diff --git a/buildroot/share/tests/BIGTREE_GTR_V1_0-tests b/buildroot/share/tests/BIGTREE_GTR_V1_0-tests index 0738a2818b..18a6a75f6f 100644 --- a/buildroot/share/tests/BIGTREE_GTR_V1_0-tests +++ b/buildroot/share/tests/BIGTREE_GTR_V1_0-tests @@ -33,6 +33,7 @@ opt_set TEMP_SENSOR_3 1 opt_set TEMP_SENSOR_4 1 opt_set TEMP_SENSOR_5 1 opt_set NUM_Z_STEPPER_DRIVERS 3 +opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED exec_test $1 $2 "BigTreeTech GTR 6 Extruders Triple Z" # clean up From 76efba686be1eaf3631f76e7bbd11d4457eab55b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Apr 2020 19:38:10 -0500 Subject: [PATCH 0244/1454] More explicit firstpush --- buildroot/share/git/firstpush | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/git/firstpush b/buildroot/share/git/firstpush index 132795b617..644ff670a1 100755 --- a/buildroot/share/git/firstpush +++ b/buildroot/share/git/firstpush @@ -14,7 +14,7 @@ FORK=${INFO[1]} REPO=${INFO[2]} BRANCH=${INFO[5]} -git push --set-upstream origin $BRANCH +git push --set-upstream origin HEAD:$BRANCH which xdg-open >/dev/null && TOOL=xdg-open which gnome-open >/dev/null && TOOL=gnome-open From d5b791a26a974a1ca134f4b91c5af1a042ad89aa Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Apr 2020 22:02:31 -0500 Subject: [PATCH 0245/1454] Fix Malyan ExtUI parse_lcd_byte See https://community.platformio.org/t/marlin-compile-fail-board-board-h-no-such-file-or-directory/11843/43 --- Marlin/src/lcd/extui_malyan_lcd.cpp | 48 +++++++++++++++++------------ 1 file changed, 28 insertions(+), 20 deletions(-) diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index ddb8b846cb..73de849087 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -71,7 +71,7 @@ #define MAX_CURLY_COMMAND (32 + LONG_FILENAME_LENGTH) * 2 // Track incoming command bytes from the LCD -int inbound_count; +uint16_t inbound_count; // For sending print completion messages bool last_printing_status = false; @@ -361,29 +361,38 @@ void process_lcd_command(const char* command) { DEBUG_ECHOLNPAIR("UNKNOWN COMMAND FORMAT ", command); } +// // Parse LCD commands mixed with G-Code -void parse_lcd_byte(byte b) { - static bool parsing_lcd_cmd = false; +// +void parse_lcd_byte(const byte b) { static char inbound_buffer[MAX_CURLY_COMMAND]; - if (!parsing_lcd_cmd) { - if (b == '{' || b == '\n' || b == '\r') { // A line-ending or opening brace - parsing_lcd_cmd = b == '{'; // Brace opens an LCD command - if (inbound_count) { // Looks like a G-code is in the buffer - inbound_buffer[inbound_count] = '\0'; // Reset before processing - inbound_count = 0; + static uint8_t parsing = 0; // Parsing state + static bool prevcr = false; // Was the last c a CR? + + const char c = b & 0x7F; + + if (parsing) { + const bool is_lcd = parsing == 1; // 1 for LCD + if ( ( is_lcd && c == '}') // Closing brace on LCD command + || (!is_lcd && c == '\n') // LF on a G-code command + ) { + inbound_buffer[inbound_count] = '\0'; // Reset before processing + parsing = 0; // Unflag and... + inbound_count = 0; // Reset buffer index + if (parsing == 1) + process_lcd_command(inbound_buffer); // Handle the LCD command + else queue.enqueue_one_now(inbound_buffer); // Handle the G-code command - } } + else if (inbound_count < MAX_CURLY_COMMAND - 2) + inbound_buffer[inbound_count++] = is_lcd ? c : b; // Buffer while space remains } - else if (b == '}') { // Closing brace on an LCD command - parsing_lcd_cmd = false; // Unflag and... - inbound_buffer[inbound_count] = '\0'; // reset before processing - inbound_count = 0; - process_lcd_command(inbound_buffer); // Handle the LCD command + else { + if (c == '{') parsing = 1; // Brace opens an LCD command + else if (prevcr && c == '\n') parsing = 2; // CRLF indicates G-code + prevcr = (c == '\r'); // Remember if it was a CR } - else if (inbound_count < MAX_CURLY_COMMAND - 2) - inbound_buffer[inbound_count++] = b; // Buffer only if space remains } /** @@ -433,9 +442,8 @@ namespace ExtUI { update_usb_status(false); // now drain commands... - while (LCD_SERIAL.available()) { - parse_lcd_byte((byte)LCD_SERIAL.read() & 0x7F); - } + while (LCD_SERIAL.available()) + parse_lcd_byte((byte)LCD_SERIAL.read()); #if ENABLED(SDSUPPORT) // The way last printing status works is simple: From 239c45dc114c33af2b444c154811c49659afad30 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 15:17:11 -0500 Subject: [PATCH 0246/1454] German language followup --- Marlin/src/lcd/language/language_de.h | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 211869fc9c..b472eaf857 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -231,7 +231,6 @@ namespace Language_de { PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Düse ~"); PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Düse geparkt"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düsen-Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Bett"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Gehäuse"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Lüfter"); From 69f211cf78c1b25469fbd1f6e4c28e0aa6dd6b0a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 15:14:32 -0500 Subject: [PATCH 0247/1454] Add empty ui.completion_feedback --- Marlin/src/lcd/menu/menu.cpp | 4 ++-- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 10 ++-------- Marlin/src/lcd/menu/menu_cancelobject.cpp | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 5 +---- Marlin/src/lcd/menu/menu_main.cpp | 2 +- Marlin/src/lcd/ultralcd.h | 2 ++ 7 files changed, 10 insertions(+), 17 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 1698c7d7ad..1518e1f50a 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -413,12 +413,12 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #if ENABLED(EEPROM_SETTINGS) void lcd_store_settings() { const bool saved = settings.save(); - TERN_(HAS_BUZZER, ui.completion_feedback(saved)); + ui.completion_feedback(saved); UNUSED(saved); } void lcd_load_settings() { const bool loaded = settings.load(); - TERN_(HAS_BUZZER, ui.completion_feedback(loaded)); + ui.completion_feedback(loaded); UNUSED(loaded); } #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 28d8411940..4f85976d7d 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -587,7 +587,7 @@ void menu_advanced_settings() { MSG_BUTTON_INIT, MSG_BUTTON_CANCEL, []{ const bool inited = settings.init_eeprom(); - TERN_(HAS_BUZZER, ui.completion_feedback(inited)); + ui.completion_feedback(inited); UNUSED(inited); }, ui.goto_previous_screen, diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 54a9cb5c23..fa7d099d15 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -48,13 +48,7 @@ static uint8_t manual_probe_index; // LCD probed points are from defaults - constexpr uint8_t total_probe_points = ( - #if ENABLED(AUTO_BED_LEVELING_3POINT) - 3 - #elif ABL_GRID || ENABLED(MESH_BED_LEVELING) - GRID_MAX_POINTS - #endif - ); + constexpr uint8_t total_probe_points = TERN(AUTO_BED_LEVELING_3POINT, 3, GRID_MAX_POINTS); // // Bed leveling is done. Wait for G29 to complete. @@ -75,7 +69,7 @@ ui.synchronize(GET_TEXT(MSG_LEVEL_BED_DONE)); #endif ui.goto_previous_screen_no_defer(); - TERN_(HAS_BUZZER, ui.completion_feedback()); + ui.completion_feedback(); } if (ui.should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT(MSG_LEVEL_BED_DONE)); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index 398dd10e2c..8b7bfc8a5c 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -44,7 +44,7 @@ static void lcd_cancel_object_confirm() { MenuItem_confirm::confirm_screen( []{ cancelable.cancel_object(MenuItemBase::itemIndex - 1); - TERN_(HAS_BUZZER, ui.completion_feedback()); + ui.completion_feedback(); ui.goto_previous_screen(); }, ui.goto_previous_screen, diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index bf7be4dbc2..cb7360d09b 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -450,10 +450,7 @@ void menu_configuration() { #endif if (!busy) - ACTION_ITEM(MSG_RESTORE_DEFAULTS, []{ - settings.reset(); - TERN_(HAS_BUZZER, ui.completion_feedback()); - }); + ACTION_ITEM(MSG_RESTORE_DEFAULTS, []{ settings.reset(); ui.completion_feedback(); }); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 4c17208b25..47873b1f44 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -239,7 +239,7 @@ void menu_main() { #if HAS_SERVICE_INTERVALS static auto _service_reset = [](const int index) { print_job_timer.resetServiceInterval(index); - TERN_(HAS_BUZZER, ui.completion_feedback()); + ui.completion_feedback(); ui.reset_status(); ui.return_to_status(); }; diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 5a4805edf7..1258d9f30e 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -397,6 +397,8 @@ public: static void quick_feedback(const bool clear_buttons=true); #if HAS_BUZZER static void completion_feedback(const bool good=true); + #else + static inline void completion_feedback(const bool=true) {} #endif #if DISABLED(LIGHTWEIGHT_UI) From 44b71103dfb7ac66847122ca2eda475beb16b4a1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 16:19:51 -0500 Subject: [PATCH 0248/1454] Patch tool_change typo --- Marlin/src/module/tool_change.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 210d220e7b..64c0503c48 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -947,7 +947,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Unload / Retract #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - const bool should_swap = can_move_away && toolchange_settings.swap_length; + const bool should_swap = can_move_away && toolchange_settings.swap_length, too_cold = TERN0(PREVENT_COLD_EXTRUSION, !DEBUGGING(DRYRUN) && (thermalManager.targetTooColdToExtrude(old_tool) || thermalManager.targetTooColdToExtrude(new_tool)) ); From b151feb31e49f10e421242e6d435da24d2191da6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 24 Apr 2020 00:03:19 +0000 Subject: [PATCH 0249/1454] [cron] Bump distribution date (2020-04-24) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c203cc6d94..9b4d21ee5a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-23" + #define STRING_DISTRIBUTION_DATE "2020-04-24" #endif /** From 07252ad0b36a9e44d818deec44ab0ae01cc073c5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 20:49:46 -0500 Subject: [PATCH 0250/1454] Update firstpush --- buildroot/share/git/firstpush | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/buildroot/share/git/firstpush b/buildroot/share/git/firstpush index 644ff670a1..9a68fc5afd 100755 --- a/buildroot/share/git/firstpush +++ b/buildroot/share/git/firstpush @@ -16,9 +16,7 @@ BRANCH=${INFO[5]} git push --set-upstream origin HEAD:$BRANCH -which xdg-open >/dev/null && TOOL=xdg-open -which gnome-open >/dev/null && TOOL=gnome-open -which open >/dev/null && TOOL=open +OPEN=$(echo $(which gnome-open xdg-open open) | awk '{ print $1 }') URL="https://github.com/$FORK/$REPO/commits/$BRANCH" if [ -z "$OPEN" ]; then From df22b96d721e0ebef5ad0bc14f225ecbd55c55a9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 21:53:28 -0500 Subject: [PATCH 0251/1454] Update mfpr --- buildroot/share/git/mfpr | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/buildroot/share/git/mfpr b/buildroot/share/git/mfpr index bff9834bc1..b853c6929e 100755 --- a/buildroot/share/git/mfpr +++ b/buildroot/share/git/mfpr @@ -23,9 +23,7 @@ OLDBRANCH=${INFO[5]} # See if it's been pushed yet if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush; fi -which xdg-open >/dev/null && TOOL=xdg-open -which gnome-open >/dev/null && TOOL=gnome-open -which open >/dev/null && TOOL=open +OPEN=$(echo $(which gnome-open xdg-open open) | awk '{ print $1 }') URL="https://github.com/$ORG/$REPO/compare/$TARG...$FORK:$BRANCH?expand=1" if [ -z "$OPEN" ]; then From 55d66fb8971d9e5dbfb15e7ae5c952839b488f59 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 20:49:11 -0500 Subject: [PATCH 0252/1454] Add HAS_JUNCTION_DEVIATION --- Marlin/Configuration.h | 2 +- Marlin/src/gcode/config/M200-M205.cpp | 4 ++-- Marlin/src/inc/Conditionals_LCD.h | 4 ++++ Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 ++-- .../screens/advanced_settings_menu.cpp | 4 ++-- .../screens/bio_advanced_settings.cpp | 4 ++-- .../screens/junction_deviation_screen.cpp | 2 +- .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 2 +- .../extui/lib/ftdi_eve_touch_ui/screens/screens.h | 4 ++-- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/lcd/extui/ui_api.h | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/module/configuration_store.cpp | 6 +++--- Marlin/src/module/planner.cpp | 14 +++++++------- Marlin/src/module/planner.h | 6 +++--- 16 files changed, 34 insertions(+), 30 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2804d8ffef..998d5ebea4 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -800,7 +800,7 @@ * https://reprap.org/forum/read.php?1,739819 * http://blog.kyneticcnc.com/2018/10/computing-junction-deviation-for-marlin.html */ -#if DISABLED(CLASSIC_JERK) +#if HAS_JUNCTION_DEVIATION #define JUNCTION_DEVIATION_MM 0.013 // (mm) Distance from real junction edge #endif diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 0ea4fd7c17..30e6f0f564 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -121,7 +121,7 @@ void GcodeSuite::M204() { * J = Junction Deviation (mm) (If not using CLASSIC_JERK) */ void GcodeSuite::M205() { - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION #define J_PARAM "J" #else #define J_PARAM @@ -137,7 +137,7 @@ void GcodeSuite::M205() { if (parser.seen('B')) planner.settings.min_segment_time_us = parser.value_ulong(); if (parser.seen('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); if (parser.seen('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION if (parser.seen('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 626d353e38..92c264a66f 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -680,6 +680,10 @@ #define HAS_CLASSIC_JERK 1 #endif +#if DISABLED(CLASSIC_JERK) + #define HAS_JUNCTION_DEVIATION 1 +#endif + // E jerk exists with JD disabled (of course) but also when Linear Advance is disabled on Delta/SCARA #if ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE)) #define HAS_CLASSIC_E_JERK 1 diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 9269c76b7d..4cefe82008 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -31,7 +31,7 @@ #endif // Linear advance uses Jerk since E is an isolated axis -#if DISABLED(CLASSIC_JERK) && ENABLED(LIN_ADVANCE) +#if HAS_JUNCTION_DEVIATION && ENABLED(LIN_ADVANCE) #define HAS_LINEAR_E_JERK 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index d1024e44ce..840e54e124 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -355,7 +355,7 @@ #error "LEVEL_BED_CORNERS requires LEVEL_CORNERS_INSET_LFRB values. Please update your Configuration.h." #elif defined(BEZIER_JERK_CONTROL) #error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION. Please update your configuration." -#elif DISABLED(CLASSIC_JERK) && defined(JUNCTION_DEVIATION_FACTOR) +#elif HAS_JUNCTION_DEVIATION && defined(JUNCTION_DEVIATION_FACTOR) #error "JUNCTION_DEVIATION_FACTOR is now JUNCTION_DEVIATION_MM. Please update your configuration." #elif defined(JUNCTION_ACCELERATION_FACTOR) #error "JUNCTION_ACCELERATION_FACTOR is obsolete. Delete it from Configuration_adv.h." @@ -1137,7 +1137,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Junction deviation is incompatible with kinematic systems. */ -#if DISABLED(CLASSIC_JERK) && IS_KINEMATIC +#if HAS_JUNCTION_DEVIATION && IS_KINEMATIC #error "CLASSIC_JERK is required for DELTA and SCARA." #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index e625325d44..41c76ad48d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -133,7 +133,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) .tag(7) .button( JERK_POS, GET_TEXT_F( - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION MSG_JUNCTION_DEVIATION #else MSG_JERK @@ -163,7 +163,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 5: GOTO_SCREEN(MaxVelocityScreen); break; case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; case 7: - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION GOTO_SCREEN(JunctionDeviationScreen); #else GOTO_SCREEN(JerkScreen); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index d2c5c6658c..ea6ba93c8b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -68,7 +68,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(7) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) .tag(8) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) .tag(9) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION .tag(10) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) #else .tag(10) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) @@ -113,7 +113,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 8: GOTO_SCREEN(MaxVelocityScreen); break; case 9: GOTO_SCREEN(DefaultAccelerationScreen); break; case 10: - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION GOTO_SCREEN(JunctionDeviationScreen); #else GOTO_SCREEN(JerkScreen); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp index 034ac15c42..afc230987e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && DISABLED(CLASSIC_JERK) +#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_JUNCTION_DEVIATION #include "screens.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index 53d9d7a5ba..72b4a8b1a5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -78,7 +78,7 @@ SCREEN_TABLE { DECL_SCREEN(MaxVelocityScreen), DECL_SCREEN(MaxAccelerationScreen), DECL_SCREEN(DefaultAccelerationScreen), -#if DISABLED(CLASSIC_JERK) +#if HAS_JUNCTION_DEVIATION DECL_SCREEN(JunctionDeviationScreen), #else DECL_SCREEN(JerkScreen), diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index c659f50fc1..87522870b9 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -58,7 +58,7 @@ enum { #if HAS_MESH BED_MESH_SCREEN_CACHE, #endif -#if DISABLED(CLASSIC_JERK) +#if HAS_JUNCTION_DEVIATION JUNC_DEV_SCREEN_CACHE, #else JERK_SCREEN_CACHE, @@ -566,7 +566,7 @@ class DefaultAccelerationScreen : public BaseNumericAdjustmentScreen, public Cac static bool onTouchHeld(uint8_t tag); }; -#if DISABLED(CLASSIC_JERK) +#if HAS_JUNCTION_DEVIATION class JunctionDeviationScreen : public BaseNumericAdjustmentScreen, public CachedScreen { public: static void onRedraw(draw_mode_t); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index dd5ddd3b66..1ae9edb7e3 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -631,7 +631,7 @@ namespace ExtUI { } #endif - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION float getJunctionDeviation_mm() { return planner.junction_deviation_mm; diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 3852686898..652f77198a 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -186,7 +186,7 @@ namespace ExtUI { void setLinearAdvance_mm_mm_s(const float, const extruder_t); #endif - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION float getJunctionDeviation_mm(); void setJunctionDeviation_mm(const float); #else diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 4f85976d7d..f6c8a2cdff 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -423,7 +423,7 @@ void menu_cancelobject(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION #if ENABLED(LIN_ADVANCE) EDIT_ITEM(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.001f, 0.3f, planner.recalculate_max_e_jerk); #else diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 84b8c75370..a919562d64 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -2393,7 +2393,7 @@ void MarlinSettings::reset() { TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;); #endif - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION planner.junction_deviation_mm = float(JUNCTION_DEVIATION_MM); #endif @@ -2862,7 +2862,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING( "Advanced: B S T" - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION " J" #endif #if HAS_CLASSIC_JERK @@ -2875,7 +2875,7 @@ void MarlinSettings::reset() { PSTR(" M205 B"), LINEAR_UNIT(planner.settings.min_segment_time_us) , PSTR(" S"), LINEAR_UNIT(planner.settings.min_feedrate_mm_s) , SP_T_STR, LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s) - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) #endif #if HAS_CLASSIC_JERK diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index c2a6365417..310e86f2e5 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -132,7 +132,7 @@ uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step -#if DISABLED(CLASSIC_JERK) +#if HAS_JUNCTION_DEVIATION float Planner::junction_deviation_mm; // (mm) M205 J #if ENABLED(LIN_ADVANCE) #if ENABLED(DISTINCT_E_FACTORS) @@ -2151,7 +2151,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(LIN_ADVANCE) - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION #if ENABLED(DISTINCT_E_FACTORS) #define MAX_E_JERK max_e_jerk[extruder] #else @@ -2238,7 +2238,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, float vmax_junction_sqr; // Initial limit on the segment entry velocity (mm/s)^2 - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION /** * Compute maximum allowable entry speed at junction by centripetal acceleration approximation. * Let a circle be tangent to both previous and current path line segments, where the junction @@ -2285,7 +2285,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, ; unit_vec *= inverse_millimeters; - #if IS_CORE && DISABLED(CLASSIC_JERK) + #if IS_CORE && HAS_JUNCTION_DEVIATION /** * On CoreXY the length of the vector [A,B] is SQRT(2) times the length of the head movement vector [X,Y]. * So taking Z and E into account, we cannot scale to a unit vector with "inverse_millimeters". @@ -2460,7 +2460,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, previous_safe_speed = safe_speed; - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION vmax_junction_sqr = _MIN(vmax_junction_sqr, sq(vmax_junction)); #else vmax_junction_sqr = sq(vmax_junction); @@ -2649,7 +2649,7 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #if IS_KINEMATIC - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION const xyze_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z, e - position_cart.e @@ -2675,7 +2675,7 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con const feedRate_t feedrate = fr_mm_s; #endif if (buffer_segment(delta.a, delta.b, delta.c, machine.e - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION , cart_dist_mm #endif , feedrate, extruder, mm diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 87a6e7c0a8..626e39c721 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -61,7 +61,7 @@ manual_feedrate_mm_s { _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, _mf.e / 60.0f }; #endif -#if IS_KINEMATIC && DISABLED(CLASSIC_JERK) +#if IS_KINEMATIC && HAS_JUNCTION_DEVIATION #define HAS_DIST_MM_ARG 1 #endif @@ -304,7 +304,7 @@ class Planner { static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 static float steps_to_mm[XYZE_N]; // Millimeters per step - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION static float junction_deviation_mm; // (mm) M205 J #if ENABLED(LIN_ADVANCE) static float max_e_jerk // Calculated from junction_deviation_mm @@ -900,7 +900,7 @@ class Planner { static void recalculate(); - #if DISABLED(CLASSIC_JERK) + #if HAS_JUNCTION_DEVIATION FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) { float magnitude_sq = 0; From ab2b98e4255b0b9579af9627e884ac3dfc1d30bb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 21:42:38 -0500 Subject: [PATCH 0253/1454] Apply composite tests --- Marlin/src/HAL/AVR/MarlinSerial.h | 2 +- Marlin/src/HAL/AVR/inc/SanityCheck.h | 4 ++-- Marlin/src/HAL/LINUX/spi_pins.h | 2 +- Marlin/src/HAL/LPC1768/spi_pins.h | 2 +- .../STM32F1/dogm/u8g_com_stm32duino_swspi.cpp | 2 +- Marlin/src/HAL/shared/HAL_ST7920.h | 2 +- Marlin/src/MarlinCore.cpp | 4 ++-- Marlin/src/feature/host_actions.cpp | 4 ++-- Marlin/src/feature/mmu2/mmu2.cpp | 4 ++-- Marlin/src/feature/mmu2/mmu2.h | 4 ++-- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 2 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 2 +- .../src/gcode/feature/digipot/M907-M910.cpp | 4 ++-- Marlin/src/gcode/gcode.cpp | 10 +++++----- Marlin/src/gcode/gcode.h | 8 ++++---- Marlin/src/gcode/temp/M155.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 10 +++++----- Marlin/src/inc/SanityCheck.h | 8 ++++---- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 4 ++-- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 10 +++++----- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 2 +- .../screens/advanced_settings_menu.cpp | 4 ++-- .../screens/bed_mesh_screen.cpp | 4 ++-- .../screens/junction_deviation_screen.cpp | 2 +- .../ftdi_eve_touch_ui/screens/main_menu.cpp | 2 +- .../screens/nozzle_offsets_screen.cpp | 2 +- .../stepper_bump_sensitivity_screen.cpp | 2 +- .../screens/stepper_current_screen.cpp | 2 +- .../screens/z_offset_screen.cpp | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 10 ++++++---- Marlin/src/lcd/menu/menu_backlash.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/lcd/menu/menu_cancelobject.cpp | 2 +- Marlin/src/lcd/menu/menu_custom.cpp | 6 ++---- Marlin/src/lcd/menu/menu_filament.cpp | 2 +- Marlin/src/lcd/menu/menu_info.cpp | 2 +- Marlin/src/lcd/menu/menu_job_recovery.cpp | 2 +- Marlin/src/lcd/menu/menu_led.cpp | 2 +- Marlin/src/lcd/menu/menu_main.cpp | 2 +- Marlin/src/lcd/menu/menu_media.cpp | 2 +- Marlin/src/lcd/menu/menu_mixer.cpp | 2 +- Marlin/src/lcd/menu/menu_mmu2.cpp | 4 ++-- Marlin/src/lcd/menu/menu_motion.cpp | 2 +- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- Marlin/src/lcd/ultralcd.cpp | 20 ++++++++----------- Marlin/src/lcd/ultralcd.h | 2 +- Marlin/src/module/configuration_store.cpp | 2 +- Marlin/src/module/motion.cpp | 12 +++++------ Marlin/src/module/probe.cpp | 2 +- Marlin/src/module/stepper.cpp | 6 +++--- Marlin/src/module/stepper.h | 4 ++-- Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h | 4 ++-- 53 files changed, 103 insertions(+), 107 deletions(-) diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index cd7aad90a9..e39ebc4037 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -304,7 +304,7 @@ static constexpr bool XONOFF = false; static constexpr bool EMERGENCYPARSER = false; static constexpr bool DROPPED_RX = false; - static constexpr bool RX_OVERRUNS = HAS_DGUS_LCD && ENABLED(DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS); + static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS); static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; }; diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 996cf52973..ccdd391114 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -46,10 +46,10 @@ /** * The Trinamic library includes SoftwareSerial.h, leading to a compile error. */ -#if HAS_TRINAMIC_CONFIG && ENABLED(ENDSTOP_INTERRUPTS_FEATURE) +#if BOTH(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) #error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif -#if HAS_TMC_SW_SERIAL && ENABLED(MONITOR_DRIVER_STATUS) +#if BOTH(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) #error "MONITOR_DRIVER_STATUS causes performance issues when used with SoftwareSerial-connected drivers. Disable MONITOR_DRIVER_STATUS or use hardware serial to continue." #endif diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index 8abeb312f4..0020e8cb79 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -24,7 +24,7 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD && ENABLED(SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) +#if BOTH(HAS_GRAPHICAL_LCD, SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index 9b983428bd..8d9738abc0 100644 --- a/Marlin/src/HAL/LPC1768/spi_pins.h +++ b/Marlin/src/HAL/LPC1768/spi_pins.h @@ -23,7 +23,7 @@ #include "../../core/macros.h" -#if ENABLED(SDSUPPORT) && HAS_GRAPHICAL_LCD && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) +#if BOTH(SDSUPPORT, HAS_GRAPHICAL_LCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index 2e9d11f97e..072b5a51a3 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -20,7 +20,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_GRAPHICAL_LCD && ENABLED(FORCE_SOFT_SPI) +#if BOTH(HAS_GRAPHICAL_LCD, FORCE_SOFT_SPI) #include "../HAL.h" #include diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h index 69c1d741ae..d70f88c032 100644 --- a/Marlin/src/HAL/shared/HAL_ST7920.h +++ b/Marlin/src/HAL/shared/HAL_ST7920.h @@ -27,7 +27,7 @@ * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate. */ -#if HAS_GRAPHICAL_LCD && ENABLED(LIGHTWEIGHT_UI) +#if BOTH(HAS_GRAPHICAL_LCD, LIGHTWEIGHT_UI) void ST7920_cs(); void ST7920_ncs(); void ST7920_set_cmd(); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index d513db668a..47b5f51d2c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -466,7 +466,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y(); if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z(); if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers(); - #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL) + #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) if (ubl.lcd_map_control) { ubl.lcd_map_control = false; ui.defer_status_screen(false); @@ -943,7 +943,7 @@ void setup() { SETUP_RUN(ui.init()); SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.) - #if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN) + #if BOTH(HAS_SPI_LCD, SHOW_BOOTSCREEN) SETUP_RUN(ui.show_bootscreen()); #endif diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 1d199a6fb6..96cfc7ed0d 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -136,14 +136,14 @@ void host_action(const char * const pstr, const bool eol) { switch (response) { case 0: // "Purge More" button - #if HAS_LCD_MENU && ENABLED(ADVANCED_PAUSE_FEATURE) + #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // Simulate menu selection (menu exits, doesn't extrude more) #endif filament_load_host_prompt(); // Initiate another host prompt. (NOTE: The loop in load_filament may also do this!) break; case 1: // "Continue" / "Disable Runout" button - #if HAS_LCD_MENU && ENABLED(ADVANCED_PAUSE_FEATURE) + #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // Simulate menu selection #endif #if HAS_FILAMENT_SENSOR diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index b26cff53b3..b69557e689 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -99,7 +99,7 @@ int16_t MMU2::version = -1, MMU2::buildnr = -1; millis_t MMU2::last_request, MMU2::next_P0_request; char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; -#if HAS_LCD_MENU && ENABLED(MMU2_MENUS) +#if BOTH(HAS_LCD_MENU, MMU2_MENUS) struct E_Step { float extrude; //!< extrude distance in mm @@ -632,7 +632,7 @@ void MMU2::filament_runout() { planner.synchronize(); } -#if HAS_LCD_MENU && ENABLED(MMU2_MENUS) +#if BOTH(HAS_LCD_MENU, MMU2_MENUS) // Load filament into MMU2 void MMU2::load_filament(uint8_t index) { diff --git a/Marlin/src/feature/mmu2/mmu2.h b/Marlin/src/feature/mmu2/mmu2.h index 970b0b4338..a887644477 100644 --- a/Marlin/src/feature/mmu2/mmu2.h +++ b/Marlin/src/feature/mmu2/mmu2.h @@ -49,7 +49,7 @@ public: static uint8_t get_current_tool(); static void set_filament_type(uint8_t index, uint8_t type); - #if HAS_LCD_MENU && ENABLED(MMU2_MENUS) + #if BOTH(HAS_LCD_MENU, MMU2_MENUS) static bool unload(); static void load_filament(uint8_t); static void load_all(); @@ -72,7 +72,7 @@ private: static bool get_response(); static void manage_response(const bool move_axes, const bool turn_off_nozzle); - #if HAS_LCD_MENU && ENABLED(MMU2_MENUS) + #if BOTH(HAS_LCD_MENU, MMU2_MENUS) static void load_to_nozzle(); static void filament_ramming(); static void execute_extruder_sequence(const E_Step * sequence, int steps); diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 165ae88709..ead70bc257 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -223,7 +223,7 @@ G29_TYPE GcodeSuite::G29() { ABL_VAR int abl_probe_index; #endif - #if HAS_SOFTWARE_ENDSTOPS && ENABLED(PROBE_MANUALLY) + #if BOTH(HAS_SOFTWARE_ENDSTOPS, PROBE_MANUALLY) ABL_VAR bool saved_soft_endstops_state = true; #endif diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 8c321df58c..f5addd9cd6 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -378,7 +378,7 @@ void GcodeSuite::G34() { // Restore the active tool after homing TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER))); // Fetch previous tool for parking extruder - #if HAS_LEVELING && ENABLED(RESTORE_LEVELING_AFTER_G34) + #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) set_bed_leveling_enabled(leveling_was_active); #endif diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 850e02e475..aee7d616a1 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M18_M84() { else planner.finish_and_disable(); - #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL) + #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) if (ubl.lcd_map_control) { ubl.lcd_map_control = false; ui.defer_status_screen(false); diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index 8f54c5d6fb..23cc349650 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || ENABLED(DAC_STEPPER_CURRENT) +#if ANY(HAS_DIGIPOTSS, HAS_MOTOR_CURRENT_PWM, HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT) #include "../../gcode.h" @@ -80,7 +80,7 @@ void GcodeSuite::M907() { #endif } -#if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) +#if EITHER(HAS_DIGIPOTSS, DAC_STEPPER_CURRENT) /** * M908: Control digital trimpot directly (M908 P S) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 693410861d..8bebeb1c15 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -70,7 +70,7 @@ uint8_t GcodeSuite::axis_relative = ( | (ar_init.e ? _BV(REL_E) : 0) ); -#if HAS_AUTO_REPORTING || ENABLED(HOST_KEEPALIVE_FEATURE) +#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) bool GcodeSuite::autoreport_paused; // = false #endif @@ -202,7 +202,7 @@ void GcodeSuite::dwell(millis_t time) { * When G29_RETRY_AND_RECOVER is enabled, call G29() in * a loop with recovery and retry handling. */ -#if HAS_LEVELING && ENABLED(G29_RETRY_AND_RECOVER) +#if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER) #ifndef G29_MAX_RETRIES #define G29_MAX_RETRIES 0 @@ -504,7 +504,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 191: M191(); break; // M191: Wait for chamber temperature to reach target #endif - #if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR + #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) case 155: M155(); break; // M155: Set temperature auto-report interval #endif @@ -792,9 +792,9 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 900: M900(); break; // M900: Set advance K factor. #endif - #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || ENABLED(DAC_STEPPER_CURRENT) + #if ANY(HAS_DIGIPOTSS, HAS_MOTOR_CURRENT_PWM, HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT) case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes. - #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) + #if EITHER(HAS_DIGIPOTSS, DAC_STEPPER_CURRENT) case 908: M908(); break; // M908: Control digital trimpot directly. #if ENABLED(DAC_STEPPER_CURRENT) case 909: M909(); break; // M909: Print digipot/DAC current value diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 98db10b08b..a3d37262f2 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -351,7 +351,7 @@ public: process_subcommands_now_P(G28_STR); } - #if HAS_AUTO_REPORTING || ENABLED(HOST_KEEPALIVE_FEATURE) + #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) static bool autoreport_paused; static inline bool set_autoreport_paused(const bool p) { const bool was = autoreport_paused; @@ -610,7 +610,7 @@ private: TERN_(HAS_COLOR_LEDS, static void M150()); - #if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR + #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) static void M155(); #endif @@ -812,9 +812,9 @@ private: static void M918(); #endif - #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || ENABLED(DAC_STEPPER_CURRENT) + #if ANY(HAS_DIGIPOTSS, HAS_MOTOR_CURRENT_PWM, HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT) static void M907(); - #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) + #if EITHER(HAS_DIGIPOTSS, DAC_STEPPER_CURRENT) static void M908(); #if ENABLED(DAC_STEPPER_CURRENT) static void M909(); diff --git a/Marlin/src/gcode/temp/M155.cpp b/Marlin/src/gcode/temp/M155.cpp index 52f9ef2be5..8859736f50 100644 --- a/Marlin/src/gcode/temp/M155.cpp +++ b/Marlin/src/gcode/temp/M155.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR +#if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) #include "../gcode.h" #include "../../module/temperature.h" diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 4cefe82008..67116f662c 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -31,7 +31,7 @@ #endif // Linear advance uses Jerk since E is an isolated axis -#if HAS_JUNCTION_DEVIATION && ENABLED(LIN_ADVANCE) +#if BOTH(HAS_JUNCTION_DEVIATION, LIN_ADVANCE) #define HAS_LINEAR_E_JERK 1 #endif @@ -1653,7 +1653,7 @@ #define HAS_TEMP_ADC_CHAMBER 1 #endif -#if HOTENDS && (HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675)) +#if HOTENDS && EITHER(HAS_TEMP_ADC_0, HEATER_0_USES_MAX6675) #define HAS_TEMP_HOTEND 1 #endif #define HAS_TEMP_BED HAS_TEMP_ADC_BED @@ -1730,7 +1730,7 @@ #endif // Thermal protection -#if HAS_HEATED_BED && ENABLED(THERMAL_PROTECTION_BED) +#if BOTH(HAS_HEATED_BED, THERMAL_PROTECTION_BED) #define HAS_THERMALLY_PROTECTED_BED 1 #endif #if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0 @@ -1739,7 +1739,7 @@ #if HAS_THERMALLY_PROTECTED_BED && WATCH_BED_TEMP_PERIOD > 0 #define WATCH_BED 1 #endif -#if HAS_HEATED_CHAMBER && ENABLED(THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 +#if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 #define WATCH_CHAMBER 1 #endif #if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) \ @@ -2142,7 +2142,7 @@ * Bed Probe dependencies */ #if HAS_BED_PROBE - #if ENABLED(ENDSTOPPULLUPS) && HAS_Z_MIN_PROBE_PIN + #if BOTH(ENDSTOPPULLUPS, HAS_Z_MIN_PROBE_PIN) #define ENDSTOPPULLUP_ZMIN_PROBE #endif #ifndef Z_PROBE_OFFSET_RANGE_MIN diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 840e54e124..7313a140c3 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -662,7 +662,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif PROGRESS_MSG_EXPIRE < 0 #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif -#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && !HAS_GRAPHICAL_LCD && DISABLED(EXTENSIBLE_UI) +#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_GRAPHICAL_LCD, EXTENSIBLE_UI) #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Graphical LCD, or EXTENSIBLE_UI." #endif @@ -673,7 +673,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Custom Boot and Status screens */ -#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && !(HAS_GRAPHICAL_LCD || ENABLED(TOUCH_UI_FTDI_EVE)) +#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(HAS_GRAPHICAL_LCD, TOUCH_UI_FTDI_EVE) #error "SHOW_CUSTOM_BOOTSCREEN requires Graphical LCD or TOUCH_UI_FTDI_EVE." #elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_GRAPHICAL_LCD #error "CUSTOM_STATUS_SCREEN_IMAGE requires a Graphical LCD." @@ -1391,7 +1391,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." #endif -#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !(ENABLED(AUTO_BED_LEVELING_UBL) && HAS_GRAPHICAL_LCD) +#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !BOTH(AUTO_BED_LEVELING_UBL, HAS_GRAPHICAL_LCD) #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." #endif @@ -1599,7 +1599,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "MAX6675_SS_PIN (required for TEMP_SENSOR_0) not defined for this board." #elif HOTENDS && !HAS_TEMP_HOTEND #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." -#elif (HAS_MULTI_HOTEND || ENABLED(HEATERS_PARALLEL)) && !HAS_HEATER_1 +#elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 #error "HEATER_1_PIN not defined for this board." #endif diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index ac4cd63322..ff76741ce7 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -275,7 +275,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS #endif // LCD_PROGRESS_BAR - #if ENABLED(SDSUPPORT) && HAS_LCD_MENU + #if BOTH(SDSUPPORT, HAS_LCD_MENU) // CHARSET_MENU const static PROGMEM byte refresh[8] = { @@ -325,7 +325,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS #endif { createChar_P(LCD_STR_UPLEVEL[0], uplevel); - #if ENABLED(SDSUPPORT) && HAS_LCD_MENU + #if BOTH(SDSUPPORT, HAS_LCD_MENU) // SD Card sub-menu special characters createChar_P(LCD_STR_REFRESH[0], refresh); createChar_P(LCD_STR_FOLDER[0], folder); diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 281bc81509..6583a767d9 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -865,7 +865,7 @@ // Can also be overridden in Configuration_adv.h // If you can afford it, try the 3-frame fan animation! // Don't compile in the fan animation with no fan -#if !HAS_FAN0 || (HOTENDS == 5 || (HOTENDS == 4 && BED_OR_CHAMBER) || (ENABLED(STATUS_COMBINE_HEATERS) && HAS_HEATED_CHAMBER)) +#if !HAS_FAN0 || (HOTENDS == 5 || (HOTENDS == 4 && BED_OR_CHAMBER) || BOTH(STATUS_COMBINE_HEATERS, HAS_HEATED_CHAMBER)) #undef STATUS_FAN_FRAMES #elif !STATUS_FAN_FRAMES #define STATUS_FAN_FRAMES 2 @@ -1393,7 +1393,7 @@ ((STATUS_CHAMBER_WIDTH || STATUS_FAN_WIDTH || STATUS_BED_WIDTH) && STATUS_HOTEND_BITMAPS == 4) #define STATUS_HEATERS_X 5 #else - #if ENABLED(STATUS_COMBINE_HEATERS) && HAS_HEATED_BED && HOTENDS <= 4 + #if BOTH(STATUS_COMBINE_HEATERS, HAS_HEATED_BED) && HOTENDS <= 4 #define STATUS_HEATERS_X 5 #else #define STATUS_HEATERS_X 8 // Like the included bitmaps @@ -1752,13 +1752,13 @@ #if HOTENDS && ENABLED(STATUS_HOTEND_ANIM) #define ANIM_HOTEND 1 #endif -#if DO_DRAW_BED && ENABLED(STATUS_BED_ANIM) +#if BOTH(DO_DRAW_BED, STATUS_BED_ANIM) #define ANIM_BED 1 #endif -#if DO_DRAW_CHAMBER && ENABLED(STATUS_CHAMBER_ANIM) +#if BOTH(DO_DRAW_CHAMBER, STATUS_CHAMBER_ANIM) #define ANIM_CHAMBER 1 #endif -#if DO_DRAW_CUTTER && ENABLED(STATUS_CUTTER_ANIM) +#if BOTH(DO_DRAW_CUTTER, STATUS_CUTTER_ANIM) #define ANIM_CUTTER 1 #endif #if ANIM_HOTEND || ANIM_BED || ANIM_CHAMBER || ANIM_CUTTER diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 537153208b..d149a9345d 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -142,7 +142,7 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #elif ANIM_HOTEND && DISABLED(STATUS_HOTEND_INVERTED) && ENABLED(STATUS_HOTEND_NUMBERLESS) #define OFF_BMP(N) status_hotend_a_bmp #define ON_BMP(N) status_hotend_b_bmp - #elif ANIM_HOTEND && ENABLED(STATUS_HOTEND_INVERTED) + #elif BOTH(ANIM_HOTEND, STATUS_HOTEND_INVERTED) #define OFF_BMP(N) status_hotend##N##_b_bmp #define ON_BMP(N) status_hotend##N##_a_bmp #else diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 41c76ad48d..2150c439e3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -38,7 +38,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { } #ifdef TOUCH_UI_PORTRAIT - #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #if EITHER(HAS_CASE_LIGHT, SENSORLESS_HOMING) #define GRID_ROWS 9 #else #define GRID_ROWS 8 @@ -59,7 +59,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1) #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) - #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #if EITHER(HAS_CASE_LIGHT, SENSORLESS_HOMING) #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) #else #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp index ff954204c0..2f015e594e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -21,7 +21,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_MESH +#if BOTH(TOUCH_UI_FTDI_EVE, HAS_MESH) #include "screens.h" #include "screen_data.h" @@ -298,4 +298,4 @@ void BedMeshScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::pr BedMeshScreen::onMeshUpdate(x, y, 0); } -#endif // TOUCH_UI_FTDI_EVE +#endif // TOUCH_UI_FTDI_EVE && HAS_MESH diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp index afc230987e..3c83e6e692 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_JUNCTION_DEVIATION +#if BOTH(TOUCH_UI_FTDI_EVE, HAS_JUNCTION_DEVIATION) #include "screens.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp index 5a81a48257..d319c6c8a6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -137,7 +137,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 4: GOTO_SCREEN(MoveAxisScreen); break; case 5: injectCommands_P(PSTR("M84")); break; case 6: GOTO_SCREEN(TemperatureScreen); break; - #if ENABLED(TOUCH_UI_COCOA_PRESS) && HAS_CASE_LIGHT + #if BOTH(TOUCH_UI_COCOA_PRESS, HAS_CASE_LIGHT) case 7: GOTO_SCREEN(CaseLightScreen); break; #else case 7: GOTO_SCREEN(ChangeFilamentScreen); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp index 9ac402e197..5b439a9133 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_MULTI_HOTEND +#if BOTH(TOUCH_UI_FTDI_EVE, HAS_MULTI_HOTEND) #include "screens.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp index 2e05ad5c57..4edfe9435e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_TRINAMIC_CONFIG +#if BOTH(TOUCH_UI_FTDI_EVE, HAS_TRINAMIC_CONFIG) #include "screens.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp index 5abcea7a67..fbba4beb8e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_TRINAMIC_CONFIG +#if BOTH(TOUCH_UI_FTDI_EVE, HAS_TRINAMIC_CONFIG) #include "screens.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp index 65a2ad0e8e..7f06514aa5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_BED_PROBE +#if BOTH(TOUCH_UI_FTDI_EVE, HAS_BED_PROBE) #include "screens.h" diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index f6c8a2cdff..1aedee4757 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -235,12 +235,14 @@ void menu_cancelobject(); #if HAS_HOTEND DEFINE_PIDTEMP_FUNCS(0); - #if HAS_MULTI_HOTEND && ENABLED(PID_PARAMS_PER_HOTEND) + #if BOTH(HAS_MULTI_HOTEND, PID_PARAMS_PER_HOTEND) REPEAT_S(1, HOTENDS, DEFINE_PIDTEMP_FUNCS) #endif #endif -#define SHOW_MENU_ADVANCED_TEMPERATURE ((ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND) || EITHER(PID_AUTOTUNE_MENU, PID_EDIT_MENU)) +#if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) || EITHER(PID_AUTOTUNE_MENU, PID_EDIT_MENU) + #define SHOW_MENU_ADVANCED_TEMPERATURE 1 +#endif // // Advanced Settings > Temperature @@ -253,7 +255,7 @@ void menu_cancelobject(); // // Autotemp, Min, Max, Fact // - #if ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND + #if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) EDIT_ITEM(bool, MSG_AUTOTEMP, &planner.autotemp_enabled); EDIT_ITEM(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - 15); EDIT_ITEM(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - 15); @@ -308,7 +310,7 @@ void menu_cancelobject(); #endif PID_EDIT_MENU_ITEMS(0); - #if HAS_MULTI_HOTEND && ENABLED(PID_PARAMS_PER_HOTEND) + #if BOTH(HAS_MULTI_HOTEND, PID_PARAMS_PER_HOTEND) REPEAT_S(1, HOTENDS, PID_EDIT_MENU_ITEMS) #endif diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 720694bfff..bbeb6829e7 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(BACKLASH_GCODE) +#if BOTH(HAS_LCD_MENU, BACKLASH_GCODE) #include "menu.h" diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 71eac08025..92ab856f61 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(LEVEL_BED_CORNERS) +#if BOTH(HAS_LCD_MENU, LEVEL_BED_CORNERS) #include "menu.h" #include "../../module/motion.h" diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index 8b7bfc8a5c..c8153fc209 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(CANCEL_OBJECTS) +#if BOTH(HAS_LCD_MENU, CANCEL_OBJECTS) #include "menu.h" #include "menu_addon.h" diff --git a/Marlin/src/lcd/menu/menu_custom.cpp b/Marlin/src/lcd/menu/menu_custom.cpp index 6f27c907a6..1ba781197f 100644 --- a/Marlin/src/lcd/menu/menu_custom.cpp +++ b/Marlin/src/lcd/menu/menu_custom.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(CUSTOM_USER_MENUS) +#if BOTH(HAS_LCD_MENU, CUSTOM_USER_MENUS) #include "menu.h" #include "../../gcode/queue.h" @@ -39,9 +39,7 @@ void _lcd_user_gcode(PGM_P const cmd) { queue.inject_P(cmd); - #if ENABLED(USER_SCRIPT_AUDIBLE_FEEDBACK) && HAS_BUZZER - ui.completion_feedback(); - #endif + TERN_(USER_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); TERN_(USER_SCRIPT_RETURN, ui.return_to_status()); } diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 5b6cbed6af..f7bc8c284c 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(ADVANCED_PAUSE_FEATURE) +#if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) #include "menu.h" #include "../../module/temperature.h" diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 284c3eb1a5..f7b895679a 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(LCD_INFO_MENU) +#if BOTH(HAS_LCD_MENU, LCD_INFO_MENU) #include "menu.h" diff --git a/Marlin/src/lcd/menu/menu_job_recovery.cpp b/Marlin/src/lcd/menu/menu_job_recovery.cpp index 31db50fe23..d19758429c 100644 --- a/Marlin/src/lcd/menu/menu_job_recovery.cpp +++ b/Marlin/src/lcd/menu/menu_job_recovery.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(POWER_LOSS_RECOVERY) +#if BOTH(HAS_LCD_MENU, POWER_LOSS_RECOVERY) #include "menu.h" #include "../../gcode/queue.h" diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index b9e75422bc..ea76ae74dd 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(LED_CONTROL_MENU) +#if BOTH(HAS_LCD_MENU, LED_CONTROL_MENU) #include "menu.h" #include "../../feature/leds/leds.h" diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 47873b1f44..a834c28aab 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -203,7 +203,7 @@ void menu_main() { GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif - #if HAS_ENCODER_WHEEL && ENABLED(SDSUPPORT) + #if BOTH(HAS_ENCODER_WHEEL, SDSUPPORT) // *** IF THIS SECTION IS CHANGED, REPRODUCE ABOVE *** diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index d818081f10..777ce1beff 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(SDSUPPORT) +#if BOTH(HAS_LCD_MENU, SDSUPPORT) #include "menu.h" #include "../../sd/cardreader.h" diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index 13c19f43fc..eeb01b62fa 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(MIXING_EXTRUDER) +#if BOTH(HAS_LCD_MENU, MIXING_EXTRUDER) #include "menu.h" #include "menu_addon.h" diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index e2f5e8d658..779f94d14f 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if HAS_LCD_MENU && ENABLED(MMU2_MENUS) +#if BOTH(HAS_LCD_MENU, MMU2_MENUS) #include "../../feature/mmu2/mmu2.h" #include "menu_mmu2.h" @@ -171,4 +171,4 @@ uint8_t mmu2_choose_filament() { return currentTool; } -#endif // HAS_LCD_MENU && ENABLED(PRUSA_MMU2_MENUS) +#endif // HAS_LCD_MENU && MMU2_MENUS diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 4c16b68b47..0e5a29c9c7 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -257,7 +257,7 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_MOTION); - #if HAS_SOFTWARE_ENDSTOPS && ENABLED(SOFT_ENDSTOPS_MENU_ITEM) + #if BOTH(HAS_SOFTWARE_ENDSTOPS, SOFT_ENDSTOPS_MENU_ITEM) EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstops_enabled); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 9ad0ac335f..e9fc6c525d 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL) +#if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) #include "menu.h" #include "../../gcode/gcode.h" diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index b427deba73..6991c681b1 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -60,7 +60,7 @@ MarlinUI ui; constexpr uint8_t MAX_MESSAGE_LENGTH = 63; #endif -#if HAS_SPI_LCD || ENABLED(EXTENSIBLE_UI) +#if EITHER(HAS_SPI_LCD, EXTENSIBLE_UI) uint8_t MarlinUI::alert_level; // = 0 char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; #endif @@ -366,7 +366,7 @@ bool MarlinUI::get_blink() { ///////////// Keypad Handling ////////////// //////////////////////////////////////////// -#if ENABLED(REPRAPWORLD_KEYPAD) && HAS_ENCODER_ACTION +#if BOTH(REPRAPWORLD_KEYPAD, HAS_ENCODER_ACTION) volatile uint8_t MarlinUI::keypad_buttons; @@ -566,7 +566,7 @@ void MarlinUI::status_screen() { if (old_frm != new_frm) { feedrate_percentage = new_frm; encoderPosition = 0; - #if HAS_BUZZER && ENABLED(BEEP_ON_FEEDRATE_CHANGE) + #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) static millis_t next_beep; #ifndef GOT_MS const millis_t ms = millis(); @@ -827,7 +827,7 @@ void MarlinUI::update() { if (encoderPastThreshold || lcd_clicked) { if (encoderPastThreshold) { - #if HAS_LCD_MENU && ENABLED(ENCODER_RATE_MULTIPLIER) + #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) int32_t encoderMultiplier = 1; @@ -888,7 +888,7 @@ void MarlinUI::update() { refresh(LCDVIEW_REDRAW_NOW); } - #if HAS_LCD_MENU && ENABLED(SCROLL_LONG_FILENAMES) + #if BOTH(HAS_LCD_MENU, SCROLL_LONG_FILENAMES) // If scrolling of long file names is enabled and we are in the sd card menu, // cause a refresh to occur until all the text has scrolled into view. if (currentScreen == menu_media && !lcd_status_update_delay--) { @@ -1134,12 +1134,8 @@ void MarlinUI::update() { #if HAS_SLOW_BUTTONS | slow_buttons #endif - #if ENABLED(TOUCH_BUTTONS) && HAS_ENCODER_ACTION - | (touch_buttons - #if HAS_ENCODER_WHEEL - & (~(EN_A | EN_B)) - #endif - ) + #if BOTH(TOUCH_BUTTONS, HAS_ENCODER_ACTION) + | (touch_buttons & TERN_(HAS_ENCODER_WHEEL, & ~(EN_A | EN_B))) #endif ); @@ -1261,7 +1257,7 @@ void MarlinUI::update() { next_filament_display = ms + 5000UL; // Show status message for 5s #endif - #if HAS_SPI_LCD && ENABLED(STATUS_MESSAGE_SCROLLING) + #if BOTH(HAS_SPI_LCD, STATUS_MESSAGE_SCROLLING) status_scroll_offset = 0; #endif diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 1258d9f30e..f6d2e86cfd 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -27,7 +27,7 @@ #include "../libs/buzzer.h" #endif -#if HAS_LCD_MENU || ENABLED(ULTIPANEL_FEEDMULTIPLY) +#if EITHER(HAS_LCD_MENU, ULTIPANEL_FEEDMULTIPLY) #define HAS_ENCODER_ACTION 1 #endif #if (!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTONS_EXIST(EN1, EN2) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index a919562d64..b38dc6caa3 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -3099,7 +3099,7 @@ void MarlinSettings::reset() { HOTEND_LOOP() { CONFIG_ECHO_START(); SERIAL_ECHOPAIR_P( - #if HAS_MULTI_HOTEND && ENABLED(PID_PARAMS_PER_HOTEND) + #if BOTH(HAS_MULTI_HOTEND, PID_PARAMS_PER_HOTEND) PSTR(" M301 E"), e, SP_P_STR #else diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 94b4316fa5..04f8507031 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -639,7 +639,7 @@ void restore_feedrate_and_scaling() { if (TERN0(DELTA, !all_axes_homed())) return; - #if HAS_HOTEND_OFFSET && ENABLED(DELTA) + #if BOTH(HAS_HOTEND_OFFSET, DELTA) // The effector center position will be the target minus the hotend offset. const xy_pos_t offs = hotend_offset[active_extruder]; #else @@ -1287,7 +1287,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t DEBUG_ECHOLNPGM(")"); } - #if HOMING_Z_WITH_PROBE && HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) + #if ALL(HOMING_Z_WITH_PROBE, HAS_HEATED_BED, WAIT_FOR_BED_HEATER) // Wait for bed to heat back up between probing points if (axis == Z_AXIS && distance < 0) thermalManager.wait_for_bed_heating(); @@ -1578,7 +1578,7 @@ void homeaxis(const AxisEnum axis) { // Fast move towards endstop until triggered if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home 1 Fast:"); - #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) if (axis == Z_AXIS && bltouch.deploy()) return; // The initial DEPLOY #endif @@ -1590,7 +1590,7 @@ void homeaxis(const AxisEnum axis) { do_homing_move(axis, 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir); - #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) if (axis == Z_AXIS) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) #endif @@ -1613,13 +1613,13 @@ void homeaxis(const AxisEnum axis) { // Slow move towards endstop until triggered if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home 2 Slow:"); - #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) if (axis == Z_AXIS && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) #endif do_homing_move(axis, 2 * bump, get_homing_bump_feedrate(axis)); - #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) if (axis == Z_AXIS) bltouch.stow(); // The final STOW #endif } diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 77e70680df..d08ba27e1b 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -441,7 +441,7 @@ bool Probe::set_deployed(const bool deploy) { bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { if (DEBUGGING(LEVELING)) DEBUG_POS(">>> Probe::probe_down_to_z", current_position); - #if HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) + #if BOTH(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) thermalManager.wait_for_bed_heating(); #endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 0119c07bea..c105570067 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -138,7 +138,7 @@ Stepper stepper; // Singleton // public: -#if HAS_EXTRA_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN) +#if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) bool Stepper::separate_multi_axis = false; #endif @@ -2265,7 +2265,7 @@ void Stepper::init() { TERN_(HAS_X2_DIR, X2_DIR_INIT()); #if HAS_Y_DIR Y_DIR_INIT(); - #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_DIR + #if BOTH(Y_DUAL_STEPPER_DRIVERS, HAS_Y2_DIR) Y2_DIR_INIT(); #endif #endif @@ -2318,7 +2318,7 @@ void Stepper::init() { #if HAS_Y_ENABLE Y_ENABLE_INIT(); if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH); - #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE + #if BOTH(Y_DUAL_STEPPER_DRIVERS, HAS_Y2_ENABLE) Y2_ENABLE_INIT(); if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH); #endif diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 3876980ad0..793dc8745b 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -240,7 +240,7 @@ class Stepper { public: - #if HAS_EXTRA_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN) + #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) static bool separate_multi_axis; #endif @@ -461,7 +461,7 @@ class Stepper { static void microstep_readings(); #endif - #if HAS_EXTRA_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN) + #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) FORCE_INLINE static void set_separate_multi_axis(const bool state) { separate_multi_axis = state; } #endif #if ENABLED(X_DUAL_ENDSTOPS) diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index dc12442224..6872adf9ba 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -115,7 +115,7 @@ // // Z Probe (when not Z_MIN_PIN) // -#if !defined(Z_MIN_PROBE_PIN) && !(HAS_CUTTER && ENABLED(BOARD_REV_1_0)) +#if !defined(Z_MIN_PROBE_PIN) && !BOTH(HAS_CUTTER, BOARD_REV_1_0) #define Z_MIN_PROBE_PIN Z_MAX_PIN #endif @@ -134,7 +134,7 @@ #define Z_DIR_PIN 39 #define Z_ENABLE_PIN 35 -#if HAS_CUTTER && ENABLED(BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 +#if BOTH(HAS_CUTTER, BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 // Move E0 to the spare and get Spindle/Laser signals from E0 #define E0_STEP_PIN 49 #define E0_DIR_PIN 47 From e11a806460d59ebf11b7ff75864ad4742222d975 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 22:35:54 -0500 Subject: [PATCH 0254/1454] Revert config replace --- Marlin/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 998d5ebea4..2804d8ffef 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -800,7 +800,7 @@ * https://reprap.org/forum/read.php?1,739819 * http://blog.kyneticcnc.com/2018/10/computing-junction-deviation-for-marlin.html */ -#if HAS_JUNCTION_DEVIATION +#if DISABLED(CLASSIC_JERK) #define JUNCTION_DEVIATION_MM 0.013 // (mm) Distance from real junction edge #endif From 2efbca55352c907e933ac31c6d4da9d1e54cedc0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Apr 2020 22:46:45 -0500 Subject: [PATCH 0255/1454] Composite test followup See ab2b98e425 --- Marlin/src/lcd/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 6991c681b1..82b93092d7 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1135,7 +1135,7 @@ void MarlinUI::update() { | slow_buttons #endif #if BOTH(TOUCH_BUTTONS, HAS_ENCODER_ACTION) - | (touch_buttons & TERN_(HAS_ENCODER_WHEEL, & ~(EN_A | EN_B))) + | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) #endif ); From cf8c14b1b0092e87aebe29c79bae0f54850c21d9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Apr 2020 01:14:34 -0500 Subject: [PATCH 0256/1454] ExtUI allow small JD mm --- Marlin/src/lcd/extui/ui_api.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 1ae9edb7e3..0e33dc5835 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -638,7 +638,7 @@ namespace ExtUI { } void setJunctionDeviation_mm(const float value) { - planner.junction_deviation_mm = constrain(value, 0.01, 0.3); + planner.junction_deviation_mm = constrain(value, 0.001, 0.3); TERN_(LIN_ADVANCE, planner.recalculate_max_e_jerk()); } From 94dd9ce73d09dfdd07b7e0fa42c15ca91761316e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 25 Apr 2020 00:03:26 +0000 Subject: [PATCH 0257/1454] [cron] Bump distribution date (2020-04-25) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9b4d21ee5a..cc786076bd 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-24" + #define STRING_DISTRIBUTION_DATE "2020-04-25" #endif /** From e25402b5411c8ea77e05f7f925e588b40b7e02a8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Apr 2020 17:41:20 -0500 Subject: [PATCH 0258/1454] Apply TERN --- Marlin/src/module/planner.cpp | 21 +++++---------------- Marlin/src/module/planner.h | 12 +++--------- 2 files changed, 8 insertions(+), 25 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 310e86f2e5..b7dc639246 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -135,19 +135,13 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step #if HAS_JUNCTION_DEVIATION float Planner::junction_deviation_mm; // (mm) M205 J #if ENABLED(LIN_ADVANCE) - #if ENABLED(DISTINCT_E_FACTORS) - float Planner::max_e_jerk[EXTRUDERS]; // Calculated from junction_deviation_mm - #else - float Planner::max_e_jerk; - #endif + float Planner::max_e_jerk // Calculated from junction_deviation_mm + TERN_(DISTINCT_E_FACTORS, [EXTRUDERS]); #endif #endif + #if HAS_CLASSIC_JERK - #if HAS_LINEAR_E_JERK - xyz_pos_t Planner::max_jerk; // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration. - #else - xyze_pos_t Planner::max_jerk; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration. - #endif + TERN(HAS_LINEAR_E_JERK, xyz_pos_t, xyze_pos_t) Planner::max_jerk; #endif #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) @@ -2382,12 +2376,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif uint8_t limited = 0; - #if HAS_LINEAR_E_JERK - LOOP_XYZ(i) - #else - LOOP_XYZE(i) - #endif - { + TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(i) { const float jerk = ABS(current_speed[i]), // cs : Starting from zero, change in speed for this axis maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis if (jerk > maxj) { // cs > mj : New current speed too fast? diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 626e39c721..8b6cdcada0 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -308,19 +308,13 @@ class Planner { static float junction_deviation_mm; // (mm) M205 J #if ENABLED(LIN_ADVANCE) static float max_e_jerk // Calculated from junction_deviation_mm - #if ENABLED(DISTINCT_E_FACTORS) - [EXTRUDERS] - #endif - ; + TERN_(DISTINCT_E_FACTORS, [EXTRUDERS]); #endif #endif #if HAS_CLASSIC_JERK - #if HAS_LINEAR_E_JERK - static xyz_pos_t max_jerk; // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration. - #else - static xyze_pos_t max_jerk; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration. - #endif + // (mm/s^2) M205 XYZ(E) - The largest speed change requiring no acceleration. + static TERN(HAS_LINEAR_E_JERK, xyz_pos_t, xyze_pos_t) max_jerk; #endif #if HAS_LEVELING From 75b91550f37935afe52493417bcb9f075a489749 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sat, 25 Apr 2020 05:16:47 +0200 Subject: [PATCH 0259/1454] Update Italian language (#17695) --- Marlin/src/lcd/language/language_it.h | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 20af26be07..0107f95e0e 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -239,6 +239,8 @@ namespace Language_it { PROGMEM Language_Str MSG_BED_Z = _UxGT("Piatto Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ugello"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Ugello ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Ugello parcheggiato"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Ugello in pausa"); PROGMEM Language_Str MSG_BED = _UxGT("Piatto"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Camera"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. ventola"); // Max 15 characters @@ -366,14 +368,23 @@ namespace Language_it { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("UnRet V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoRitrai"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Dist. ritrazione"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lunghezza scambio"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra scambio"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lunghezza spurgo"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambio utensile"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Risalita Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocità innesco"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Velocità retrazione"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Ugello Parcheggiato"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Standby ugello"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Parcheggia testa"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Velocità ventola"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Tempo ventola"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Migrazione utensile"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migrazione"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Ultimo estrusore"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migra a *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambia filamento *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Carica filamento"); From 4af83430b523bd44451aae85ea507bc7d2f2f2c3 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Sat, 25 Apr 2020 05:20:24 +0200 Subject: [PATCH 0260/1454] ReARM SDSS pin for RRD LCDs (#17698) --- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 52dd9b2eb5..f25b0fcc3d 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -353,7 +353,7 @@ #define SD_DETECT_PIN P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 - #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 + #define LCD_SDSS P1_23 // (53) J3-5 & AUX-3 #if ENABLED(NEWPANEL) #if ENABLED(REPRAPWORLD_KEYPAD) From d7f90c36dfa5062c49206b6084137dce2344512c Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sat, 25 Apr 2020 05:27:58 +0200 Subject: [PATCH 0261/1454] Fix SAMD51 Step Timer (#17692) --- Marlin/src/HAL/SAMD51/timers.cpp | 7 ++++--- Marlin/src/HAL/SAMD51/timers.h | 6 +++--- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index 3eb021c25b..158ea4ed17 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -121,14 +121,15 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { tc->COUNT32.CTRLA.bit.SWRST = true; SYNC(tc->COUNT32.SYNCBUSY.bit.SWRST); - // Wave mode, reset counter on overflow on 0 (I use count down to prevent double buffer use) + // Wave mode, reset counter on compare match tc->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ; tc->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCALER_DIV1; - tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_DIR; + tc->COUNT32.CTRLBCLR.reg = TC_CTRLBCLR_DIR; SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB); // Set compare value - tc->COUNT32.COUNT.reg = tc->COUNT32.CC[0].reg = (HAL_TIMER_RATE) / frequency; + tc->COUNT32.CC[0].reg = (HAL_TIMER_RATE) / frequency; + tc->COUNT32.COUNT.reg = 0; // Enable interrupt on compare tc->COUNT32.INTFLAG.reg = TC_INTFLAG_OVF; // reset pending interrupt diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index 4b21e47162..69793ea58d 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -97,13 +97,13 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { // Should never be called with timer RTC_TIMER_NUM Tc * const tc = TimerConfig[timer_num].pTc; - tc->COUNT32.CC[0].reg = HAL_TIMER_TYPE_MAX - compare; + tc->COUNT32.CC[0].reg = compare; } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { // Should never be called with timer RTC_TIMER_NUM Tc * const tc = TimerConfig[timer_num].pTc; - return (hal_timer_t)(HAL_TIMER_TYPE_MAX - tc->COUNT32.CC[0].reg); + return (hal_timer_t)tc->COUNT32.CC[0].reg; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { @@ -111,7 +111,7 @@ FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { Tc * const tc = TimerConfig[timer_num].pTc; tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC; SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB || tc->COUNT32.SYNCBUSY.bit.COUNT); - return HAL_TIMER_TYPE_MAX - tc->COUNT32.COUNT.reg; + return tc->COUNT32.COUNT.reg; } void HAL_timer_enable_interrupt(const uint8_t timer_num); From 3a27933ae7c874c6a33c5300ebee517756883c76 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Apr 2020 22:35:46 -0500 Subject: [PATCH 0262/1454] Fixes for FYSETC Touch EVE 5" on AVR (#17659) Co-Authored-By: RudolphRiedel Co-authored-by: sL1pKn07 --- Marlin/Configuration_adv.h | 10 +- Marlin/src/inc/Conditionals_LCD.h | 2 +- .../ftdi_eve_lib/basic/commands.cpp | 96 +++++++++--------- .../ftdi_eve_lib/basic/spi.cpp | 34 +++---- .../ftdi_eve_lib/basic/spi.h | 12 ++- .../ftdi_eve_lib/extended/sound_list.h | 4 +- .../lib/ftdi_eve_touch_ui/pin_mappings.h | 9 ++ .../screens/about_screen.cpp | 2 +- .../screens/interface_settings_screen.cpp | 4 + Marlin/src/pins/ramps/pins_RAMPS.h | 44 +++++++++ Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 99 ++++++++++++++++--- .../src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 89 +++++++++++++---- 12 files changed, 294 insertions(+), 111 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 75c86931c7..7472c39a26 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1375,10 +1375,12 @@ //#define TOUCH_UI_800x480 // Mappings for boards with a standard RepRapDiscount Display connector - //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping - //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping - //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping - //#define S6_TFT_PINMAP // FYSETC S6 pin mapping + //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping + //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping + //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping + //#define S6_TFT_PINMAP // FYSETC S6 pin mapping + //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, FYSETC Cheetah and Stock boards) EXP1 pin mapping + //#define GENERIC_EXP2_PINMAP // GENERIC EXP2 pin mapping //#define OTHER_PIN_LAYOUT // Define pins manually below #if ENABLED(OTHER_PIN_LAYOUT) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 92c264a66f..14aa031ac6 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -361,7 +361,7 @@ #define HAS_DGUS_LCD 1 #endif -// Extensible UI serial touch screens. (See src/lcd/extensible_ui) +// Extensible UI serial touch screens. (See src/lcd/extui) #if ANY(HAS_DGUS_LCD, MALYAN_LCD, TOUCH_UI_FTDI_EVE) #define IS_EXTUI #define EXTENSIBLE_UI diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 42ba64de7c..58008d2449 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -58,7 +58,7 @@ void CLCD::FontMetrics::load(const uint8_t font) { uint16_t CLCD::FontMetrics::get_text_width(const char *str, size_t n) const { uint16_t width = 0; const uint8_t *p = (const uint8_t *) str; - for(;;) { + for (;;) { const uint8_t val = *p++; n--; if (!val || n == 0) break; width += val < 128 ? char_widths[val] : 0; @@ -69,7 +69,7 @@ uint16_t CLCD::FontMetrics::get_text_width(const char *str, size_t n) const { uint16_t CLCD::FontMetrics::get_text_width(progmem_str str, size_t n) const { uint16_t width = 0; const uint8_t *p = (const uint8_t *) str; - for(;;) { + for (;;) { const uint8_t val = pgm_read_byte(p++); n--; if (!val || n == 0) break; width += val < 128 ? char_widths[val] : 0; @@ -79,7 +79,7 @@ uint16_t CLCD::FontMetrics::get_text_width(progmem_str str, size_t n) const { /************************** HOST COMMAND FUNCTION *********************************/ -void CLCD::host_cmd (unsigned char host_command, unsigned char byte2) { // Sends 24-Bit Host Command to LCD +void CLCD::host_cmd(unsigned char host_command, unsigned char byte2) { // Sends 24-Bit Host Command to LCD if (host_command != FTDI::ACTIVE) { host_command |= 0x40; } @@ -92,7 +92,7 @@ void CLCD::host_cmd (unsigned char host_command, unsigned char byte2) { // Send /************************** MEMORY READ FUNCTIONS *********************************/ -void CLCD::spi_read_addr (uint32_t reg_address) { +void CLCD::spi_read_addr(uint32_t reg_address) { spi_send((reg_address >> 16) & 0x3F); // Address [21:16] spi_send((reg_address >> 8 ) & 0xFF); // Address [15:8] spi_send((reg_address >> 0) & 0xFF); // Address [7:0] @@ -100,7 +100,7 @@ void CLCD::spi_read_addr (uint32_t reg_address) { } // Write 4-Byte Address, Read Multiple Bytes -void CLCD::mem_read_bulk (uint32_t reg_address, uint8_t *data, uint16_t len) { +void CLCD::mem_read_bulk(uint32_t reg_address, uint8_t *data, uint16_t len) { spi_ftdi_select(); spi_read_addr(reg_address); spi_read_bulk (data, len); @@ -108,7 +108,7 @@ void CLCD::mem_read_bulk (uint32_t reg_address, uint8_t *data, uint16_t len) { } // Write 4-Byte Address, Read 1-Byte Data -uint8_t CLCD::mem_read_8 (uint32_t reg_address) { +uint8_t CLCD::mem_read_8(uint32_t reg_address) { spi_ftdi_select(); spi_read_addr(reg_address); uint8_t r_data = spi_read_8(); @@ -117,7 +117,7 @@ uint8_t CLCD::mem_read_8 (uint32_t reg_address) { } // Write 4-Byte Address, Read 2-Bytes Data -uint16_t CLCD::mem_read_16 (uint32_t reg_address) { +uint16_t CLCD::mem_read_16(uint32_t reg_address) { using namespace SPI::least_significant_byte_first; spi_ftdi_select(); spi_read_addr(reg_address); @@ -127,7 +127,7 @@ uint16_t CLCD::mem_read_16 (uint32_t reg_address) { } // Write 4-Byte Address, Read 4-Bytes Data -uint32_t CLCD::mem_read_32 (uint32_t reg_address) { +uint32_t CLCD::mem_read_32(uint32_t reg_address) { using namespace SPI::least_significant_byte_first; spi_ftdi_select(); spi_read_addr(reg_address); @@ -147,14 +147,14 @@ static inline uint8_t reverse_byte(uint8_t a) { } static inline uint8_t xbm_write(const uint8_t *p) {return reverse_byte(pgm_read_byte(p));} -void CLCD::spi_write_addr (uint32_t reg_address) { +void CLCD::spi_write_addr(uint32_t reg_address) { spi_send((reg_address >> 16) | 0x80); // Address [21:16] spi_send((reg_address >> 8 ) & 0xFF); // Address [15:8] spi_send((reg_address >> 0) & 0xFF); // Address [7:0] } // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from RAM -void CLCD::mem_write_bulk (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding) { +void CLCD::mem_write_bulk(uint32_t reg_address, const void *data, uint16_t len, uint8_t padding) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_bulk(data, len, padding); @@ -162,7 +162,7 @@ void CLCD::mem_write_bulk (uint32_t reg_address, const void *data, uint16_t len, } // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM -void CLCD::mem_write_bulk (uint32_t reg_address, progmem_str str, uint16_t len, uint8_t padding) { +void CLCD::mem_write_bulk(uint32_t reg_address, progmem_str str, uint16_t len, uint8_t padding) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_bulk(str, len, padding); @@ -170,7 +170,7 @@ void CLCD::mem_write_bulk (uint32_t reg_address, progmem_str str, uint16_t len, } // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM -void CLCD::mem_write_pgm (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding) { +void CLCD::mem_write_pgm(uint32_t reg_address, const void *data, uint16_t len, uint8_t padding) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_bulk(data, len, padding); @@ -178,7 +178,7 @@ void CLCD::mem_write_pgm (uint32_t reg_address, const void *data, uint16_t len, } // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM, reversing bytes (suitable for loading XBM images) -void CLCD::mem_write_xbm (uint32_t reg_address, progmem_str data, uint16_t len, uint8_t padding) { +void CLCD::mem_write_xbm(uint32_t reg_address, progmem_str data, uint16_t len, uint8_t padding) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_bulk(data, len, padding); @@ -186,7 +186,7 @@ void CLCD::mem_write_xbm (uint32_t reg_address, progmem_str data, uint16_t len, } // Write 3-Byte Address, Write 1-Byte Data -void CLCD::mem_write_8 (uint32_t reg_address, uint8_t data) { +void CLCD::mem_write_8(uint32_t reg_address, uint8_t data) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_8(data); @@ -194,16 +194,16 @@ void CLCD::mem_write_8 (uint32_t reg_address, uint8_t data) { } // Write 3-Byte Address, Write 2-Bytes Data -void CLCD::mem_write_16 (uint32_t reg_address, uint16_t data) { +void CLCD::mem_write_16(uint32_t reg_address, uint16_t data) { using namespace SPI::least_significant_byte_first; spi_ftdi_select(); spi_write_addr(reg_address); - spi_write_32(data); + spi_write_16(data); spi_ftdi_deselect(); } // Write 3-Byte Address, Write 4-Bytes Data -void CLCD::mem_write_32 (uint32_t reg_address, uint32_t data) { +void CLCD::mem_write_32(uint32_t reg_address, uint32_t data) { using namespace SPI::least_significant_byte_first; spi_ftdi_select(); spi_write_addr(reg_address); @@ -281,7 +281,7 @@ void CLCD::CommandFifo::text(int16_t x, int16_t y, int16_t font, uint16_t optio } // This sends the a toggle command to the command preprocessor, must be followed by str() -void CLCD::CommandFifo::toggle (int16_t x, int16_t y, int16_t w, int16_t font, uint16_t options, bool state) { +void CLCD::CommandFifo::toggle(int16_t x, int16_t y, int16_t w, int16_t font, uint16_t options, bool state) { struct { int32_t type = CMD_TOGGLE; int16_t x; @@ -303,7 +303,7 @@ void CLCD::CommandFifo::toggle (int16_t x, int16_t y, int16_t w, int16_t font, u } // This sends the a keys command to the command preprocessor, must be followed by str() -void CLCD::CommandFifo::keys (int16_t x, int16_t y, int16_t w, int16_t h, int16_t font, uint16_t options) { +void CLCD::CommandFifo::keys(int16_t x, int16_t y, int16_t w, int16_t h, int16_t font, uint16_t options) { struct { int32_t type = CMD_KEYS; int16_t x; @@ -324,7 +324,7 @@ void CLCD::CommandFifo::keys (int16_t x, int16_t y, int16_t w, int16_t h, int16_ cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::clock (int16_t x, int16_t y, int16_t r, uint16_t options, int16_t h, int16_t m, int16_t s, int16_t ms) +void CLCD::CommandFifo::clock(int16_t x, int16_t y, int16_t r, uint16_t options, int16_t h, int16_t m, int16_t s, int16_t ms) { struct { int32_t type = CMD_CLOCK; @@ -350,7 +350,7 @@ void CLCD::CommandFifo::clock (int16_t x, int16_t y, int16_t r, uint16_t options cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::gauge (int16_t x, int16_t y, int16_t r, uint16_t options, uint16_t major, uint16_t minor, uint16_t val, uint16_t range) +void CLCD::CommandFifo::gauge(int16_t x, int16_t y, int16_t r, uint16_t options, uint16_t major, uint16_t minor, uint16_t val, uint16_t range) { struct { int32_t type = CMD_GAUGE; @@ -376,7 +376,7 @@ void CLCD::CommandFifo::gauge (int16_t x, int16_t y, int16_t r, uint16_t options cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::dial (int16_t x, int16_t y, int16_t r, uint16_t options, uint16_t val) +void CLCD::CommandFifo::dial(int16_t x, int16_t y, int16_t r, uint16_t options, uint16_t val) { struct { int32_t type = CMD_DIAL; @@ -396,7 +396,7 @@ void CLCD::CommandFifo::dial (int16_t x, int16_t y, int16_t r, uint16_t options, cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::scrollbar (int16_t x, int16_t y, int16_t w, int16_t h, uint16_t options, uint16_t val, uint16_t size, uint16_t range) { +void CLCD::CommandFifo::scrollbar(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t options, uint16_t val, uint16_t size, uint16_t range) { struct { int32_t type = CMD_SCROLLBAR; int16_t x; @@ -421,7 +421,7 @@ void CLCD::CommandFifo::scrollbar (int16_t x, int16_t y, int16_t w, int16_t h, u cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::progress (int16_t x, int16_t y, int16_t w, int16_t h, uint16_t options, uint16_t val, uint16_t range) { +void CLCD::CommandFifo::progress(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t options, uint16_t val, uint16_t range) { struct { int32_t type = CMD_PROGRESS; int16_t x; @@ -444,7 +444,7 @@ void CLCD::CommandFifo::progress (int16_t x, int16_t y, int16_t w, int16_t h, ui cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::slider (int16_t x, int16_t y, int16_t w, int16_t h, uint16_t options, uint16_t val, uint16_t range) { +void CLCD::CommandFifo::slider(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t options, uint16_t val, uint16_t range) { struct { int32_t type = CMD_SLIDER; int16_t x; @@ -467,7 +467,7 @@ void CLCD::CommandFifo::slider (int16_t x, int16_t y, int16_t w, int16_t h, uint cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::gradient (int16_t x0, int16_t y0, uint32_t rgb0, int16_t x1, int16_t y1, uint32_t rgb1) { +void CLCD::CommandFifo::gradient(int16_t x0, int16_t y0, uint32_t rgb0, int16_t x1, int16_t y1, uint32_t rgb1) { struct { int32_t type = CMD_GRADIENT; int16_t x0; @@ -488,7 +488,7 @@ void CLCD::CommandFifo::gradient (int16_t x0, int16_t y0, uint32_t rgb0, int16_t cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::number (int16_t x, int16_t y, int16_t font, uint16_t options, int32_t n) { +void CLCD::CommandFifo::number(int16_t x, int16_t y, int16_t font, uint16_t options, int32_t n) { struct { int32_t type = CMD_NUMBER; int16_t x; @@ -507,7 +507,7 @@ void CLCD::CommandFifo::number (int16_t x, int16_t y, int16_t font, uint16_t opt cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::memzero (uint32_t ptr, uint32_t size) { +void CLCD::CommandFifo::memzero(uint32_t ptr, uint32_t size) { struct { uint32_t type = CMD_MEMZERO; uint32_t ptr; @@ -520,7 +520,7 @@ void CLCD::CommandFifo::memzero (uint32_t ptr, uint32_t size) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::memset (uint32_t ptr, uint32_t val, uint32_t size) { +void CLCD::CommandFifo::memset(uint32_t ptr, uint32_t val, uint32_t size) { struct { uint32_t type = CMD_MEMSET; uint32_t ptr; @@ -535,7 +535,7 @@ void CLCD::CommandFifo::memset (uint32_t ptr, uint32_t val, uint32_t size) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::memcpy (uint32_t dst, uint32_t src, uint32_t size) { +void CLCD::CommandFifo::memcpy(uint32_t dst, uint32_t src, uint32_t size) { struct { uint32_t type = CMD_MEMCPY; uint32_t dst; @@ -550,7 +550,7 @@ void CLCD::CommandFifo::memcpy (uint32_t dst, uint32_t src, uint32_t size) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::memcrc (uint32_t ptr, uint32_t num, uint32_t result) { +void CLCD::CommandFifo::memcrc(uint32_t ptr, uint32_t num, uint32_t result) { struct { uint32_t type = CMD_MEMCRC; uint32_t ptr; @@ -565,7 +565,7 @@ void CLCD::CommandFifo::memcrc (uint32_t ptr, uint32_t num, uint32_t result) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::memwrite (uint32_t ptr, uint32_t value) { +void CLCD::CommandFifo::memwrite(uint32_t ptr, uint32_t value) { struct { uint32_t type = CMD_MEMWRITE; uint32_t ptr; @@ -580,7 +580,7 @@ void CLCD::CommandFifo::memwrite (uint32_t ptr, uint32_t value) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::append (uint32_t ptr, uint32_t size) { +void CLCD::CommandFifo::append(uint32_t ptr, uint32_t size) { struct { uint32_t type = CMD_APPEND; uint32_t ptr; @@ -593,7 +593,7 @@ void CLCD::CommandFifo::append (uint32_t ptr, uint32_t size) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::inflate (uint32_t ptr) { +void CLCD::CommandFifo::inflate(uint32_t ptr) { struct { uint32_t type = CMD_INFLATE; uint32_t ptr; @@ -604,7 +604,7 @@ void CLCD::CommandFifo::inflate (uint32_t ptr) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::getptr (uint32_t result) { +void CLCD::CommandFifo::getptr(uint32_t result) { struct { uint32_t type = CMD_GETPTR; uint32_t result; @@ -696,7 +696,7 @@ void CLCD::CommandFifo::loadimage(uint32_t ptr, uint32_t options) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::getprops (uint32_t ptr, uint32_t width, uint32_t height) { +void CLCD::CommandFifo::getprops(uint32_t ptr, uint32_t width, uint32_t height) { struct { uint32_t type = CMD_GETPROPS; uint32_t ptr; @@ -735,7 +735,7 @@ void CLCD::CommandFifo::rotate(int32_t a) { cmd( &cmd_data, sizeof(cmd_data) ); } -void CLCD::CommandFifo::translate (int32_t tx, int32_t ty) { +void CLCD::CommandFifo::translate(int32_t tx, int32_t ty) { struct { uint32_t type = CMD_TRANSLATE; int32_t tx; @@ -749,7 +749,7 @@ void CLCD::CommandFifo::translate (int32_t tx, int32_t ty) { } #if FTDI_API_LEVEL >= 810 -void CLCD::CommandFifo::setbase (uint8_t base) { +void CLCD::CommandFifo::setbase(uint8_t base) { struct { int32_t type = CMD_SETBASE; uint32_t base; @@ -855,7 +855,7 @@ void CLCD::CommandFifo::playvideo(uint32_t options) { #endif #if FTDI_API_LEVEL >= 810 -void CLCD::CommandFifo::setrotate (uint8_t rotation) { +void CLCD::CommandFifo::setrotate(uint8_t rotation) { struct { uint32_t type = CMD_SETROTATE; uint32_t rotation; @@ -868,7 +868,7 @@ void CLCD::CommandFifo::setrotate (uint8_t rotation) { #endif #if FTDI_API_LEVEL >= 810 -void CLCD::CommandFifo::romfont (uint8_t font, uint8_t romslot) { +void CLCD::CommandFifo::romfont(uint8_t font, uint8_t romslot) { struct { uint32_t type = CMD_ROMFONT; uint32_t font; @@ -1054,18 +1054,12 @@ void CLCD::init() { spi_init(); // Set Up I/O Lines for SPI and FT800/810 Control ftdi_reset(); // Power down/up the FT8xx with the apropriate delays - if (Use_Crystal == 1) { - host_cmd(CLKEXT, 0); - } - else { - host_cmd(CLKINT, 0); - } - + host_cmd(Use_Crystal ? CLKEXT : CLKINT, 0); host_cmd(FTDI::ACTIVE, 0); // Activate the System Clock /* read the device-id until it returns 0x7c or times out, should take less than 150ms */ uint8_t counter; - for(counter = 0; counter < 250; counter++) { + for (counter = 0; counter < 250; counter++) { uint8_t device_id = mem_read_8(REG::ID); // Read Device ID, Should Be 0x7C; if (device_id == 0x7c) { #if ENABLED(TOUCH_UI_DEBUG) @@ -1073,9 +1067,9 @@ void CLCD::init() { #endif break; } - else { + else delay(1); - } + if (counter == 249) { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); @@ -1130,7 +1124,7 @@ void CLCD::init() { mem_write_8(REG::PCLK, Pclk); // Turns on Clock by setting PCLK Register to the value necessary for the module - mem_write_16(REG::PWM_HZ, 0x00FA); + mem_write_16(REG::PWM_HZ, ENABLED(LCD_FYSETC_TFT81050) ? 0x2710 : 0x00FA); // Turning off dithering seems to help prevent horizontal line artifacts on certain colors mem_write_8(REG::DITHER, 0); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 6621ea3cbf..9506eefc44 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -27,7 +27,11 @@ /********************************* SPI Functions *********************************/ namespace FTDI { + #ifndef CLCD_USE_SOFT_SPI + #ifndef __AVR__ + SPIClass EVE_SPI(CLCD_SPI_BUS); + #endif SPISettings SPI::spi_settings(SPI_FREQUENCY, MSBFIRST, SPI_MODE0); #endif @@ -57,12 +61,12 @@ namespace FTDI { SET_INPUT_PULLUP(CLCD_SOFT_SPI_MISO); #else - ::SPI.begin(); + SPI_OBJ.begin(); #endif } #ifdef CLCD_USE_SOFT_SPI - uint8_t SPI::_soft_spi_xfer (uint8_t spiOutByte) { + uint8_t SPI::_soft_spi_xfer(uint8_t spiOutByte) { uint8_t spiIndex = 0x80; uint8_t spiInByte = 0; uint8_t k; @@ -71,8 +75,8 @@ namespace FTDI { for (k = 0; k < 8; k++) { // Output and Read each bit of spiOutByte and spiInByte WRITE(CLCD_SOFT_SPI_MOSI, (spiOutByte & spiIndex) ? 1 : 0); // Output MOSI Bit WRITE(CLCD_SOFT_SPI_SCLK, 1); // Pulse Clock + if (READ(CLCD_SOFT_SPI_MISO)) spiInByte |= spiIndex; // MISO changes on the falling edge of clock, so sample it before WRITE(CLCD_SOFT_SPI_SCLK, 0); - if (READ(CLCD_SOFT_SPI_MISO)) spiInByte |= spiIndex; spiIndex >>= 1; } interrupts(); @@ -81,7 +85,7 @@ namespace FTDI { #endif #ifdef CLCD_USE_SOFT_SPI - void SPI::_soft_spi_send (uint8_t spiOutByte) { + void SPI::_soft_spi_send(uint8_t spiOutByte) { uint8_t k, spiIndex = 0x80; noInterrupts(); @@ -95,16 +99,12 @@ namespace FTDI { } #endif - void SPI::spi_read_bulk (void *data, uint16_t len) { + void SPI::spi_read_bulk(void *data, uint16_t len) { uint8_t* p = (uint8_t *)data; - #ifndef CLCD_USE_SOFT_SPI - ::SPI.transfer(p, len); - #else - while (len--) *p++ = spi_recv(); - #endif + while (len--) *p++ = spi_recv(); } - bool SPI::spi_verify_bulk (const void *data, uint16_t len) { + bool SPI::spi_verify_bulk(const void *data, uint16_t len) { const uint8_t* p = (const uint8_t *)data; while (len--) if (*p++ != spi_recv()) return false; return true; @@ -113,7 +113,7 @@ namespace FTDI { // CLCD SPI - Chip Select void SPI::spi_ftdi_select() { #ifndef CLCD_USE_SOFT_SPI - ::SPI.beginTransaction(spi_settings); + SPI_OBJ.beginTransaction(spi_settings); #endif WRITE(CLCD_SPI_CS, 0); #ifdef CLCD_SPI_EXTRA_CS @@ -129,25 +129,25 @@ namespace FTDI { WRITE(CLCD_SPI_EXTRA_CS, 1); #endif #ifndef CLCD_USE_SOFT_SPI - ::SPI.endTransaction(); + SPI_OBJ.endTransaction(); #endif } #ifdef SPI_FLASH_SS // Serial SPI Flash SPI - Chip Select - void SPI::spi_flash_select () { + void SPI::spi_flash_select() { #ifndef CLCD_USE_SOFT_SPI - ::SPI.beginTransaction(spi_settings); + SPI_OBJ.beginTransaction(spi_settings); #endif WRITE(SPI_FLASH_SS, 0); delayMicroseconds(1); } // Serial SPI Flash SPI - Chip Deselect - void SPI::spi_flash_deselect () { + void SPI::spi_flash_deselect() { WRITE(SPI_FLASH_SS, 1); #ifndef CLCD_USE_SOFT_SPI - ::SPI.endTransaction(); + SPI_OBJ.endTransaction(); #endif } #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h index 38f0e35d5a..763f5ccb1d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h @@ -27,6 +27,14 @@ #endif namespace FTDI { + + #if defined(__AVR__) || defined(CLCD_USE_SOFT_SPI) + #define SPI_OBJ ::SPI + #else + extern SPIClass EVE_SPI; + #define SPI_OBJ EVE_SPI + #endif + namespace SPI { #ifndef CLCD_USE_SOFT_SPI extern SPISettings spi_settings; @@ -47,7 +55,7 @@ namespace FTDI { #ifdef CLCD_USE_SOFT_SPI return _soft_spi_xfer(0x00); #else - return ::SPI.transfer(0x00); + SPI_OBJ.transfer(0x00); #endif }; @@ -55,7 +63,7 @@ namespace FTDI { #ifdef CLCD_USE_SOFT_SPI _soft_spi_send(val); #else - ::SPI.transfer(val); + SPI_OBJ.transfer(val); #endif }; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h index a53ed95159..dcfa290230 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h @@ -30,9 +30,9 @@ class SoundList { public: static const uint8_t n; static inline const char* name(uint8_t val) { - return (const char* ) pgm_read_ptr_near(&list[val].name); + return (const char* ) pgm_read_ptr_far(&list[val].name); } static inline FTDI::SoundPlayer::sound_t* data(uint8_t val) { - return (FTDI::SoundPlayer::sound_t*) pgm_read_ptr_near(&list[val].data); + return (FTDI::SoundPlayer::sound_t*) pgm_read_ptr_far(&list[val].data); } }; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 1780c587e1..21f4769bea 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -154,3 +154,12 @@ #define CLCD_SPI_EXTRA_CS SDSS #endif #endif + +#if EITHER(E3_EXP1_PINMAP, GENERIC_EXP2_PINMAP) + #ifndef __MARLIN_FIRMWARE__ + #error "This pin mapping requires Marlin." + #endif + + #define CLCD_MOD_RESET BTN_EN1 + #define CLCD_SPI_CS LCD_PINS_RS +#endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp index 5ddc4b650c..48b65608f2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp @@ -82,7 +82,7 @@ void AboutScreen::onRedraw(draw_mode_t) { ); draw_text_box(cmd, FW_VERS_POS, progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); - draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + draw_text_box(cmd.tag(3), INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); cmd.font(font_medium) .colors(normal_btn) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index d893518275..7f179aa6f0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -74,7 +74,9 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { #define EDGE_R 30 .font(font_small) .tag(0) + #if DISABLED(LCD_FYSETC_TFT81050) .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) + #endif .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) @@ -93,7 +95,9 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { cmd.font(font_medium) #define EDGE_R 30 .colors(ui_slider) + #if DISABLED(LCD_FYSETC_TFT81050) .tag(2).slider(BTN_POS(3,2), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.brightness, 128) + #endif .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) .colors(ui_toggle) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index be3f33ebfd..71d8813ed9 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -721,3 +721,47 @@ #define BTN_ENC 63 #endif #endif + +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. Comment out this line to continue." + + /** FYSECT TFT TFT81050 display pinout + * + * Board Display + * _____ _____ + * (SCK) D52 | 1 2 | D50 (MISO) MISO | 1 2 | SCK + * (SD_CS) D53 | 3 4 | D33 (BNT_EN2) (BNT_EN2) MOD_RESET | 3 4 | SD_CS + * (MOSI) D51 | 5 6 D31 (BNT_EN1) (BNT_EN1) LCD_CS | 5 6 MOSI + * RESET | 7 8 | D49 (SD_DET) SD_DET | 7 8 | RESET + * NC | 9 10| GND GND | 9 10| 5V + * ----- ----- + * EXP2 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP2-1 ----------- EXP1-10 + * EXP2-2 ----------- EXP1-9 + * EXP2-4 ----------- EXP1-8 + * EXP2-4 ----------- EXP1-7 + * EXP2-3 ----------- EXP1-6 + * EXP2-6 ----------- EXP1-5 + * EXP2-7 ----------- EXP1-4 + * EXP2-8 ----------- EXP1-3 + * EXP2-1 ----------- EXP1-2 + * EXT1-10 ----------- EXP1-1 + * + */ + + #define BEEPER_PIN 37 + + #define BTN_EN1 31 + #define LCD_PINS_RS 33 + + #define SD_DETECT_PIN 49 + + #define KILL_PIN -1 + +#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 569e29a96a..dc19373c18 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -47,20 +47,20 @@ // // Limit Switches // -#define X_STOP_PIN PC1 // X-STOP -#define Y_STOP_PIN PC0 // Y-STOP -#define Z_STOP_PIN PC15 // Z-STOP +#define X_STOP_PIN PC1 // "X-STOP" +#define Y_STOP_PIN PC0 // "Y-STOP" +#define Z_STOP_PIN PC15 // "Z-STOP" // // Z Probe must be this pin // -#define Z_MIN_PROBE_PIN PC14 // PROBE +#define Z_MIN_PROBE_PIN PC14 // "PROBE" // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PC2 // E0-STOP + #define FIL_RUNOUT_PIN PC2 // "E0-STOP" #endif // @@ -149,9 +149,9 @@ // // Heaters / Fans // -#define HEATER_0_PIN PC8 // HE -#define HEATER_BED_PIN PC9 // HB -#define FAN_PIN PA8 // FAN0 +#define HEATER_0_PIN PC8 // "HE" +#define HEATER_BED_PIN PC9 // "HB" +#define FAN_PIN PA8 // "FAN0" // // USB connect control @@ -159,8 +159,6 @@ #define USB_CONNECT_PIN PC13 #define USB_CONNECT_INVERTING false -#define SD_DETECT_PIN PC4 - /** * _____ * 5V | 1 2 | GND @@ -182,18 +180,31 @@ #define EXPA1_10_PIN PA15 #if HAS_SPI_LCD - #define BTN_ENC EXPA1_09_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN #if ENABLED(CR10_STOCKDISPLAY) #define BEEPER_PIN EXPA1_10_PIN + #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define LCD_PINS_RS EXPA1_04_PIN #define LCD_PINS_ENABLE EXPA1_03_PIN #define LCD_PINS_D4 EXPA1_05_PIN + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." + + #define LCD_PINS_RS EXPA1_05_PIN + #define LCD_PINS_ENABLE EXPA1_09_PIN + #define LCD_PINS_D4 EXPA1_04_PIN + #define LCD_PINS_D5 EXPA1_06_PIN + #define LCD_PINS_D6 EXPA1_08_PIN + #define LCD_PINS_D7 EXPA1_10_PIN + #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! + #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout @@ -207,6 +218,10 @@ * EXP1 */ + #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define DOGLCD_CS EXPA1_04_PIN #define DOGLCD_A0 EXPA1_05_PIN #define DOGLCD_SCK EXPA1_10_PIN @@ -215,17 +230,71 @@ #define LCD_BACKLIGHT_PIN -1 #else - #error "Only CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY, and MKS_MINI_12864 are currently supported on the BIGTREE_SKR_E3_DIP." + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, and MKS_MINI_12864 are currently supported on the BIGTREE_SKR_E3_DIP." #endif #endif // HAS_SPI_LCD +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. Comment out this line to continue." + + /** FYSECT TFT TFT81050 display pinout + * + * Board Display + * _____ _____ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 PA10 (SD_CS) (PB8) LCD_CS | 5 6 MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PA15) SD_DET | 7 8 | RESET + * (BEEPER) PB6 | 9 10| PA15 (SD_DET) GND | 9 10| 5V + * ----- ----- + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- EXP1-5 + * SP11-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- EXP1-8 + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXT1-10 ----------- EXP1-4 + * + */ + + #define CLCD_SPI_BUS 1 // SPI1 connector + + #define BEEPER_PIN EXPA1_09_PIN + + #define BTN_EN1 EXPA1_08_PIN + #define LCD_PINS_RS EXPA1_04_PIN + +#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 + // // SD Support // + #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif -#define ON_BOARD_SPI_DEVICE 1 //SPI1 +#if SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN PC4 +#endif + +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) && SD_CONNECTION_IS(LCD) + #define SD_DETECT_PIN EXPA1_10_PIN + #define SS_PIN EXPA1_06_PIN +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "SD CUSTOM_CABLE is not compatible with SKR E3 DIP." +#endif + +#define ON_BOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 5896f38f3d..7dffe76de1 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -40,19 +40,19 @@ // // Servos // -#define SERVO0_PIN PA1 +#define SERVO0_PIN PA1 // "SERVOS" // // Limit Switches // -#define X_STOP_PIN PC0 -#define Y_STOP_PIN PC1 -#define Z_STOP_PIN PC2 +#define X_STOP_PIN PC0 // "X-STOP" +#define Y_STOP_PIN PC1 // "Y-STOP" +#define Z_STOP_PIN PC2 // "Z-STOP" // -// Z Probe must be this pins +// Z Probe must be this pin // -#define Z_MIN_PROBE_PIN PC14 +#define Z_MIN_PROBE_PIN PC14 // "PROBE" // // Filament Runout Sensor @@ -83,15 +83,15 @@ // // Temperature Sensors // -#define TEMP_0_PIN PA0 // Analog Input -#define TEMP_BED_PIN PC3 // Analog Input +#define TEMP_0_PIN PA0 // Analog Input "TH0" +#define TEMP_BED_PIN PC3 // Analog Input "TB0" // // Heaters / Fans // -#define HEATER_0_PIN PC8 // EXTRUDER -#define HEATER_BED_PIN PC9 // BED -#define FAN_PIN PA8 +#define HEATER_0_PIN PC8 // "HE" +#define HEATER_BED_PIN PC9 // "HB" +#define FAN_PIN PA8 // "FAN0" // // USB connect control @@ -99,8 +99,6 @@ #define USB_CONNECT_PIN PC13 #define USB_CONNECT_INVERTING false -#define SD_DETECT_PIN PC4 - /** * _____ * 5V | 1 2 | GND @@ -127,9 +125,9 @@ #define BEEPER_PIN EXPA1_10_PIN + #define BTN_ENC EXPA1_09_PIN #define BTN_EN1 EXPA1_08_PIN #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN #define LCD_PINS_RS EXPA1_04_PIN #define LCD_PINS_ENABLE EXPA1_03_PIN @@ -159,9 +157,10 @@ * ----- * EXP1 */ + + #define BTN_ENC EXPA1_09_PIN #define BTN_EN1 EXPA1_08_PIN #define BTN_EN2 EXPA1_06_PIN - #define BTN_ENC EXPA1_09_PIN #define DOGLCD_CS EXPA1_04_PIN #define DOGLCD_A0 EXPA1_05_PIN @@ -171,19 +170,73 @@ #define LCD_BACKLIGHT_PIN -1 #else - - #error "Only ZONESTAR_LCD, MKS_MINI_12864, ENDER2_STOCKDISPLAY, and CR10_STOCKDISPLAY are currently supported on the BIGTREE_SKR_MINI_E3." - + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, and MKS_MINI_12864 are currently supported on the BIGTREE_SKR_MINI_E3." #endif #endif // HAS_SPI_LCD +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." + + /** FYSECT TFT TFT81050 display pinout + * + * Board Display + * _____ _____ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 PA10 (SD_CS) (PB8) LCD_CS | 5 6 MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET + * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V + * ----- ----- + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- EXP1-5 + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- EXP1-8 + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-4 + * + */ + + #define CLCD_SPI_BUS 1 // SPI1 connector + + #define BEEPER_PIN EXPA1_09_PIN + + #define BTN_EN1 EXPA1_08_PIN + #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_ENABLE EXPA1_03_PIN + #define LCD_PINS_D4 EXPA1_05_PIN + +#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 + // // SD Support // + #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif +#if SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN PC4 +#endif + +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) && SD_CONNECTION_IS(LCD) + #define SD_DETECT_PIN EXPA1_10_PIN + #define SS_PIN EXPA1_06_PIN +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." +#endif + #define ON_BOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card From d2a5d51f69ff35961d65577f4855e63d123381fd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ond=C5=99ej=20Nov=C3=BD?= Date: Sat, 25 Apr 2020 05:39:08 +0200 Subject: [PATCH 0263/1454] Add NOZZLE_PARK_Z_RAISE_MIN (#17624) --- Marlin/Configuration.h | 3 ++- Marlin/src/feature/mmu2/mmu2.cpp | 2 +- Marlin/src/feature/pause.cpp | 2 +- Marlin/src/libs/nozzle.cpp | 11 +++++++++-- 4 files changed, 13 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2804d8ffef..dc02515273 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1501,8 +1501,9 @@ #if ENABLED(NOZZLE_PARK_FEATURE) // Specify a park position as { X, Y, Z_raise } #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } + #define NOZZLE_PARK_Z_RAISE_MIN 2 // (mm) Always raise Z by at least this distance #define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis) - #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers) + #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers) #endif /** diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index b69557e689..e0b738c5ff 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -575,7 +575,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { resume_position = current_position; if (move_axes && all_axes_homed()) - nozzle.park(2, park_point /*= NOZZLE_PARK_POINT*/); + nozzle.park(0, park_point /*= NOZZLE_PARK_POINT*/); if (turn_off_nozzle) thermalManager.setTargetHotend(0, active_extruder); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 64ef914372..4b50d3df26 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -412,7 +412,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) if (!axes_need_homing()) - nozzle.park(2, park_point); + nozzle.park(0, park_point); #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index c691a7db3b..b83ec4280a 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -177,8 +177,15 @@ Nozzle nozzle; do_blocking_move_to_z(_MIN(current_position.z + park.z, Z_MAX_POS), fr_z); break; - default: // Raise to at least the Z-park height - do_blocking_move_to_z(_MAX(park.z, current_position.z), fr_z); + default: { + // Apply a minimum raise, overriding G27 Z + const float min_raised_z =_MIN(Z_MAX_POS, current_position.z + #ifdef NOZZLE_PARK_Z_RAISE_MIN + + NOZZLE_PARK_Z_RAISE_MIN + #endif + ); + do_blocking_move_to_z(_MAX(park.z, min_raised_z), fr_z); + } break; } do_blocking_move_to_xy(park, fr_xy); From 58ac9f257cb73a0607e3821591f3dfea75670d27 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Sat, 25 Apr 2020 17:42:34 +0200 Subject: [PATCH 0264/1454] NOZZLE_PARK_FEATURE - X/Y only axis move (#17697) --- Marlin/Configuration.h | 2 ++ Marlin/src/libs/nozzle.cpp | 6 +++++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index dc02515273..a69cecf4a0 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1501,6 +1501,8 @@ #if ENABLED(NOZZLE_PARK_FEATURE) // Specify a park position as { X, Y, Z_raise } #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } + //#define NOZZLE_PARK_X_ONLY // X move only is required to park + //#define NOZZLE_PARK_Y_ONLY // Y move only is required to park #define NOZZLE_PARK_Z_RAISE_MIN 2 // (mm) Always raise Z by at least this distance #define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis) #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers) diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index b83ec4280a..926845ced2 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -188,7 +188,11 @@ Nozzle nozzle; } break; } - do_blocking_move_to_xy(park, fr_xy); + do_blocking_move_to_xy( + TERN(NOZZLE_PARK_Y_ONLY, current_position, park).x, + TERN(NOZZLE_PARK_X_ONLY, current_position, park).y, + fr_xy + ); report_current_position(); } From be7e04056fa6e90eb46bb339ac4964a551b3e62e Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sat, 25 Apr 2020 17:44:46 +0200 Subject: [PATCH 0265/1454] Update Italian language (#17707) --- Marlin/src/lcd/language/language_it.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 0107f95e0e..2b903d80a1 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -386,11 +386,11 @@ namespace Language_it { PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Ultimo estrusore"); PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migra a *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambia filamento *"); + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambia filam. *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Carica filamento"); PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Carica filamento *"); PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Rimuovi filamento"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Rimuovi filamento *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Rimuovi filam. *"); PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Rimuovi tutto"); PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Collega media"); PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambia media"); From 4d3a2bd22cd259ae5fb05231d0a70c6b55183187 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sat, 25 Apr 2020 17:56:56 +0200 Subject: [PATCH 0266/1454] Clean up filament change menu (#17702) Co-authored-by: Scott Lahteine --- Marlin/src/lcd/menu/menu_filament.cpp | 44 ++++++++++++--------------- 1 file changed, 20 insertions(+), 24 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index f7bc8c284c..46aee8f7a9 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -39,28 +39,26 @@ // // Change Filament > Change/Unload/Load Filament // -static PauseMode _change_filament_temp_mode; // =PAUSE_MODE_PAUSE_PRINT -static int8_t _change_filament_temp_extruder; // =0 +static PauseMode _change_filament_mode; // = PAUSE_MODE_PAUSE_PRINT +static int8_t _change_filament_extruder; // = 0 -inline PGM_P _change_filament_temp_command() { - switch (_change_filament_temp_mode) { - case PAUSE_MODE_LOAD_FILAMENT: - return PSTR("M701 T%d"); - case PAUSE_MODE_UNLOAD_FILAMENT: - return _change_filament_temp_extruder >= 0 ? PSTR("M702 T%d") : PSTR("M702 ;%d"); +inline PGM_P _change_filament_command() { + switch (_change_filament_mode) { + case PAUSE_MODE_LOAD_FILAMENT: return PSTR("M701 T%d"); + case PAUSE_MODE_UNLOAD_FILAMENT: return _change_filament_extruder >= 0 + ? PSTR("M702 T%d") : PSTR("M702 ;%d"); case PAUSE_MODE_CHANGE_FILAMENT: case PAUSE_MODE_PAUSE_PRINT: - default: - return PSTR("M600 B0 T%d"); + default: break; } - return GET_TEXT(MSG_FILAMENTCHANGE); + return PSTR("M600 B0 T%d"); } // Initiate Filament Load/Unload/Change at the specified temperature -static void _change_filament_temp(const uint16_t temperature) { +static void _change_filament(const uint16_t celsius) { char cmd[11]; - sprintf_P(cmd, _change_filament_temp_command(), _change_filament_temp_extruder); - thermalManager.setTargetHotend(temperature, _change_filament_temp_extruder); + sprintf_P(cmd, _change_filament_command(), _change_filament_extruder); + thermalManager.setTargetHotend(celsius, _change_filament_extruder); queue.inject(cmd); } @@ -70,25 +68,23 @@ static void _change_filament_temp(const uint16_t temperature) { inline PGM_P change_filament_header(const PauseMode mode) { switch (mode) { - case PAUSE_MODE_LOAD_FILAMENT: - return GET_TEXT(MSG_FILAMENTLOAD); - case PAUSE_MODE_UNLOAD_FILAMENT: - return GET_TEXT(MSG_FILAMENTUNLOAD); + case PAUSE_MODE_LOAD_FILAMENT: return GET_TEXT(MSG_FILAMENTLOAD); + case PAUSE_MODE_UNLOAD_FILAMENT: return GET_TEXT(MSG_FILAMENTUNLOAD); default: break; } return GET_TEXT(MSG_FILAMENTCHANGE); } void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { - _change_filament_temp_mode = mode; - _change_filament_temp_extruder = extruder; + _change_filament_mode = mode; + _change_filament_extruder = extruder; START_MENU(); if (LCD_HEIGHT >= 4) STATIC_ITEM_P(change_filament_header(mode), SS_CENTER|SS_INVERT); BACK_ITEM(MSG_BACK); - ACTION_ITEM(MSG_PREHEAT_1, []{ _change_filament_temp(ui.preheat_hotend_temp[0]); }); - ACTION_ITEM(MSG_PREHEAT_2, []{ _change_filament_temp(ui.preheat_hotend_temp[1]); }); - EDIT_ITEM_FAST(int3, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[_change_filament_temp_extruder].target, EXTRUDE_MINTEMP, heater_maxtemp[extruder] - 15, []{ - _change_filament_temp(thermalManager.temp_hotend[_change_filament_temp_extruder].target); + ACTION_ITEM(MSG_PREHEAT_1, []{ _change_filament(ui.preheat_hotend_temp[0]); }); + ACTION_ITEM(MSG_PREHEAT_2, []{ _change_filament(ui.preheat_hotend_temp[1]); }); + EDIT_ITEM_FAST(int3, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[_change_filament_extruder].target, EXTRUDE_MINTEMP, heater_maxtemp[extruder] - 15, []{ + _change_filament(thermalManager.temp_hotend[_change_filament_extruder].target); }); END_MENU(); } From 307c48fe0a80cd6991f36ec336400db07c386a56 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 11:24:29 -0500 Subject: [PATCH 0267/1454] Parity between LPC176x pins --- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 6 ++++-- Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h | 6 ++++-- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 6 ++++-- 16 files changed, 64 insertions(+), 32 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 1417fb7d99..bba63febd9 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -34,8 +34,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index d710138b95..fa3a2cc844 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -41,8 +41,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Limit Switches diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index 041235d493..eb384f4566 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -39,8 +39,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Limit Switches diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 4dae2dc5d6..4a029db60f 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -26,8 +26,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Limit Switches diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 32de7bb740..b272575e19 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -33,8 +33,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Enable 12MHz clock output on P1.27 pin to sync TMC2208 chip clocks diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index afbe6d5564..8dcb194d33 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -35,8 +35,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index f25b0fcc3d..f4acfb7ba1 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -45,8 +45,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 6f84f87bba..5e2b10ef6f 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -35,8 +35,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index 95cbd2163e..5df52908f4 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -35,8 +35,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h index 1e5d2f3a2c..e16a1b90b6 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h @@ -34,8 +34,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // DIGIPOT slave addresses diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h index a8649b6f8d..974537ee11 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h @@ -27,8 +27,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Include SKR 1.4 pins diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index f696d060db..adb3bc04f5 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -34,8 +34,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 179909a4ce..c9b13b234e 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -34,8 +34,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index fd98b5ef13..713eca2944 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -35,8 +35,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif #define MKS_HAS_LPC1769 #include "../lpc1768/pins_MKS_SBASE.h" diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index 43db07ea5e..0a3be9aff4 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -35,8 +35,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index d4e87e24dd..0836e1ff5a 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -35,8 +35,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif // // Servos From b700b3cde6102cff68f25555bffe5f112e2111e4 Mon Sep 17 00:00:00 2001 From: randellhodges Date: Sat, 25 Apr 2020 11:35:35 -0500 Subject: [PATCH 0268/1454] Fix M261, i2c EEPROM, i2c Encoder for LPC (#17678) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/shared/eeprom_i2c.cpp | 12 ++++++------ Marlin/src/core/macros.h | 6 +----- Marlin/src/feature/encoder_i2c.cpp | 4 ++-- Marlin/src/feature/twibus.cpp | 4 ++-- 4 files changed, 11 insertions(+), 15 deletions(-) diff --git a/Marlin/src/HAL/shared/eeprom_i2c.cpp b/Marlin/src/HAL/shared/eeprom_i2c.cpp index 3eb72194ac..8ce3b88c48 100644 --- a/Marlin/src/HAL/shared/eeprom_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_i2c.cpp @@ -39,7 +39,7 @@ // Private Variables // ------------------------ -static uint8_t eeprom_device_address = 0x50; +static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(0x50); // ------------------------ // Public functions @@ -54,7 +54,7 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) { eeprom_init(); - Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address)); + Wire.beginTransmission(eeprom_device_address); Wire.write((int)(eeprom_address >> 8)); // MSB Wire.write((int)(eeprom_address & 0xFF)); // LSB Wire.write(value); @@ -70,7 +70,7 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) { void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) { eeprom_init(); - Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address)); + Wire.beginTransmission(eeprom_device_address); Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB Wire.endTransmission(); @@ -82,7 +82,7 @@ void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) { flag |= Wire.read() ^ ptr[c]; if (flag) { - Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address)); + Wire.beginTransmission(eeprom_device_address); Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB Wire.write((uint8_t*)pos, n); @@ -99,7 +99,7 @@ uint8_t eeprom_read_byte(uint8_t *pos) { eeprom_init(); - Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address)); + Wire.beginTransmission(eeprom_device_address); Wire.write((int)(eeprom_address >> 8)); // MSB Wire.write((int)(eeprom_address & 0xFF)); // LSB Wire.endTransmission(); @@ -111,7 +111,7 @@ uint8_t eeprom_read_byte(uint8_t *pos) { void eeprom_read_block(void* pos, const void* eeprom_address, size_t n) { eeprom_init(); - Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address)); + Wire.beginTransmission(eeprom_device_address); Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB Wire.endTransmission(); diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 899baf7359..765f157e2f 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -292,11 +292,7 @@ #define FMOD(x, y) fmodf(x, y) #define HYPOT(x,y) SQRT(HYPOT2(x,y)) -#ifdef TARGET_LPC1768 - #define I2C_ADDRESS(A) ((A) << 1) -#else - #define I2C_ADDRESS(A) A -#endif +#define I2C_ADDRESS(A) (TERN(TARGET_LPC1768, (A) << 1, A)) // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index dfc29a70d3..dfac6ccdf5 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -305,7 +305,7 @@ int32_t I2CPositionEncoder::get_raw_count() { encoderCount.val = 0x00; - if (Wire.requestFrom((int)i2cAddress, 3) != 3) { + if (Wire.requestFrom(I2C_ADDRESS(i2cAddress), 3) != 3) { //houston, we have a problem... H = I2CPE_MAG_SIG_NF; return 0; @@ -744,7 +744,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) { Wire.endTransmission(); // Read value - if (Wire.requestFrom((int)address, 32)) { + if (Wire.requestFrom(I2C_ADDRESS(address), 32)) { char c; while (Wire.available() > 0 && (c = (char)Wire.read()) > 0) SERIAL_ECHO(c); diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 9dbb1deb4f..4ed9faaa8a 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -104,8 +104,8 @@ bool TWIBus::request(const uint8_t bytes) { debug(PSTR("request"), bytes); // requestFrom() is a blocking function - if (Wire.requestFrom(addr, bytes) == 0) { - debug("request fail", addr); + if (Wire.requestFrom(I2C_ADDRESS(addr), bytes) == 0) { + debug("request fail", I2C_ADDRESS(addr)); return false; } From 11f7695907711041a6d716f229367d06e6a09db0 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Sat, 25 Apr 2020 18:47:19 +0200 Subject: [PATCH 0269/1454] Touch UI FTDI EVE is now beta (#17704) --- .../extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp | 2 +- .../lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 58008d2449..1c297d6acd 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -1124,7 +1124,7 @@ void CLCD::init() { mem_write_8(REG::PCLK, Pclk); // Turns on Clock by setting PCLK Register to the value necessary for the module - mem_write_16(REG::PWM_HZ, ENABLED(LCD_FYSETC_TFT81050) ? 0x2710 : 0x00FA); + mem_write_16(REG::PWM_HZ, 0x00FA); // Turning off dithering seems to help prevent horizontal line artifacts on certain colors mem_write_8(REG::DITHER, 0); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 7f179aa6f0..b04cfae7fc 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -161,7 +161,7 @@ void InterfaceSettingsScreen::onIdle() { CommandProcessor cmd; switch (cmd.track_tag(value)) { case 2: - screen_data.InterfaceSettingsScreen.brightness = constrain((value * 128UL) / 0xFFFF, 1, 11); + screen_data.InterfaceSettingsScreen.brightness = _MAX(11, (value * 128UL) / 0xFFFF); CLCD::set_brightness(screen_data.InterfaceSettingsScreen.brightness); SaveSettingsDialogBox::settingsChanged(); break; diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 71d8813ed9..c27b766688 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -751,7 +751,7 @@ * EXP2-7 ----------- EXP1-4 * EXP2-8 ----------- EXP1-3 * EXP2-1 ----------- EXP1-2 - * EXT1-10 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-1 * */ diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index dc19373c18..ea5fdaa6da 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -264,7 +264,7 @@ * EXP1-7 ----------- EXP1-8 * EXP1-8 ----------- EXP1-3 * SPI1-1 ----------- EXP1-1 - * EXT1-10 ----------- EXP1-4 + * EXP1-10 ----------- EXP1-7 * */ diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 7dffe76de1..6658f1fd8f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -204,7 +204,7 @@ * EXP1-7 ----------- EXP1-8 * EXP1-8 ----------- EXP1-3 * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-4 + * EXP1-10 ----------- EXP1-7 * */ From aa832a05c76c133e7680d5ed76bd268b36ddb3b6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 12:02:16 -0500 Subject: [PATCH 0270/1454] Use MCP4451 interface for MKS SBASE Followup to #17536 --- Marlin/src/inc/SanityCheck.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 7313a140c3..8d4b9d33bd 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2462,8 +2462,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if HAS_I2C_DIGIPOT #if BOTH(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #error "Enable only one of DIGIPOT_MCP4018 or DIGIPOT_MCP4451." - #elif !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \ - || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1) + #elif !MB(MKS_SBASE) \ + && (!defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1)) #error "DIGIPOT_MCP4018/4451 requires DIGIPOTS_I2C_SDA_* pins to be defined." #endif #endif From 28518c2352efb71e335990413f93220347410618 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Sat, 25 Apr 2020 19:20:42 +0200 Subject: [PATCH 0271/1454] Save/Restore leveling on toolchange for singlenozzle too (#17682) --- Marlin/src/module/tool_change.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 64c0503c48..d7f6ef15cc 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -914,7 +914,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { const uint8_t old_tool = active_extruder; const bool can_move_away = !no_move && !idex_full_control; - #if HAS_LEVELING && DISABLED(SINGLENOZZLE) + #if HAS_LEVELING // Set current position to the physical position TEMPORARY_BED_LEVELING_STATE(false); #endif From 75c17c7a67843b0464d8dc005bf93a856639da62 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 26 Apr 2020 06:29:30 +1200 Subject: [PATCH 0272/1454] Include echo: with M503 output (#17665) --- Marlin/src/module/configuration_store.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index b38dc6caa3..72336f7cc1 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -2824,8 +2824,8 @@ void MarlinSettings::reset() { #endif ); #if ENABLED(DISTINCT_E_FACTORS) - CONFIG_ECHO_START(); LOOP_L_N(i, E_STEPPERS) { + CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( PSTR(" M203 T"), (int)i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) @@ -2844,12 +2844,13 @@ void MarlinSettings::reset() { #endif ); #if ENABLED(DISTINCT_E_FACTORS) - CONFIG_ECHO_START(); - LOOP_L_N(i, E_STEPPERS) + LOOP_L_N(i, E_STEPPERS) { + CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( PSTR(" M201 T"), (int)i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]) ); + } #endif CONFIG_ECHO_HEADING("Acceleration (units/s2): P R T"); @@ -3522,12 +3523,14 @@ void MarlinSettings::reset() { */ #if ENABLED(LIN_ADVANCE) CONFIG_ECHO_HEADING("Linear Advance:"); - CONFIG_ECHO_START(); #if EXTRUDERS < 2 + CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR(" M900 K", planner.extruder_advance_K[0]); #else - LOOP_L_N(i, EXTRUDERS) + LOOP_L_N(i, EXTRUDERS) { + CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR(" M900 T", int(i), " K", planner.extruder_advance_K[i]); + } #endif #endif From f907de272aa8bbb5c9d25ae1473d395271e94044 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 16:49:53 -0500 Subject: [PATCH 0273/1454] Fix mesh point sign Most obvious part of #17670 Co-Authored-By: FilippoR --- Marlin/src/lcd/menu/menu_ubl.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index e9fc6c525d..31459cf215 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -41,7 +41,8 @@ static int16_t ubl_storage_slot = 0, ubl_fillin_amount = 5, ubl_height_amount = 1; -static uint8_t n_edit_pts = 1, x_plot = 0, y_plot = 0; +static uint8_t n_edit_pts = 1; +static int8_t x_plot = 0, y_plot = 0; // May be negative during move #if HAS_HEATED_BED static int16_t custom_bed_temp = 50; From 489554623822017d10249daf640c8b7334f25b9c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 26 Apr 2020 00:15:43 +0000 Subject: [PATCH 0274/1454] [cron] Bump distribution date (2020-04-26) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cc786076bd..51cf3ef084 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-25" + #define STRING_DISTRIBUTION_DATE "2020-04-26" #endif /** From 1752cd4fe5f6e91ad6923b59aa39cb794d435dfb Mon Sep 17 00:00:00 2001 From: Axel Date: Sat, 25 Apr 2020 21:03:16 -0400 Subject: [PATCH 0275/1454] Add a Mightyboard pin (#17538) Co-authored-by: Scott Lahteine --- Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index f3d338aa2a..b3a9f39167 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -203,6 +203,7 @@ #define LED_PIN 13 // B7 #define CUTOFF_RESET_PIN 16 // H1 #define CUTOFF_TEST_PIN 17 // H0 +#define CUTOFF_SR_CHECK_PIN 70 // G4 (TOSC1) // // LCD / Controller From 02a054cda466fc8d4e417b0049a0272dd78f90ba Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 25 Apr 2020 18:56:54 -0700 Subject: [PATCH 0276/1454] HOME_BEFORE_FILAMENT_CHANGE on any axis unknown (#17681) --- Marlin/src/gcode/feature/pause/M600.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index be4390aafc..5193864a07 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -97,7 +97,7 @@ void GcodeSuite::M600() { #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) // Don't allow filament change without homing first - if (axes_need_homing()) home_all_axes(); + if (!all_axes_known()) home_all_axes(); #endif #if EXTRUDERS > 1 From 21067ab06217835d232e9610d8dace2d243428ba Mon Sep 17 00:00:00 2001 From: Toni Date: Sun, 26 Apr 2020 04:07:21 +0200 Subject: [PATCH 0277/1454] Add Prusa MMU2S settings - beta (#17523) --- Marlin/Configuration_adv.h | 19 ++++ Marlin/src/feature/mmu2/mmu2.cpp | 128 +++++++++++++++++++------- Marlin/src/feature/mmu2/mmu2.h | 10 ++ Marlin/src/inc/SanityCheck.h | 2 + Marlin/src/lcd/language/language_en.h | 18 ++-- buildroot/share/tests/mega2560-tests | 2 +- 6 files changed, 138 insertions(+), 41 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7472c39a26..e01f71d7e2 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3267,6 +3267,25 @@ { 10.0, 700 }, \ { -10.0, 400 }, \ { -50.0, 2000 } + #endif + + // Using a sensor like the MMU2S + //#define PRUSA_MMU2_S_MODE + #if ENABLED(PRUSA_MMU2_S_MODE) + #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) + + #define MMU2_CAN_LOAD_FEEDRATE 800 // (mm/m) + #define MMU2_CAN_LOAD_SEQUENCE \ + { 0.1, MMU2_CAN_LOAD_FEEDRATE }, \ + { 60.0, MMU2_CAN_LOAD_FEEDRATE }, \ + { -52.0, MMU2_CAN_LOAD_FEEDRATE } + + #define MMU2_CAN_LOAD_RETRACT 6.0 // (mm) Keep under the distance between Load Sequence values + #define MMU2_CAN_LOAD_DEVIATION 0.8 // (mm) Acceptable deviation + + #define MMU2_CAN_LOAD_INCREMENT 0.2 // (mm) To reuse within MMU2 module + #define MMU2_CAN_LOAD_INCREMENT_SEQUENCE \ + { -MMU2_CAN_LOAD_INCREMENT, MMU2_CAN_LOAD_FEEDRATE } #endif diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index e0b738c5ff..3bb5d9e7ee 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -91,6 +91,9 @@ MMU2 mmu2; #define mmuSerial MMU2_SERIAL bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved; +#if ENABLED(PRUSA_MMU2_S_MODE) + bool MMU2::mmu2s_triggered; +#endif uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder; int8_t MMU2::state = 0; volatile int8_t MMU2::finda = 1; @@ -106,8 +109,14 @@ char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; feedRate_t feedRate; //!< feed rate in mm/s }; - static constexpr E_Step ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE }; - static constexpr E_Step load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE }; + static constexpr E_Step + ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE } + , load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE } + #if ENABLED(PRUSA_MMU2_S_MODE) + , can_load_sequence[] PROGMEM = { MMU2_CAN_LOAD_SEQUENCE } + , can_load_increment_sequence[] PROGMEM = { MMU2_CAN_LOAD_INCREMENT_SEQUENCE } + #endif + ; #endif // MMU2_MENUS @@ -228,6 +237,7 @@ void MMU2::mmu_loop() { enabled = true; state = 1; + TERN_(PRUSA_MMU2_S_MODE, mmu2s_triggered = false); } break; @@ -291,6 +301,8 @@ void MMU2::mmu_loop() { tx_str_P(PSTR("P0\n")); state = 2; // wait for response } + + TERN_(PRUSA_MMU2_S_MODE, check_filament()); break; case 2: // response to command P0 @@ -309,6 +321,7 @@ void MMU2::mmu_loop() { else if (ELAPSED(millis(), last_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s) state = 1; + TERN_(PRUSA_MMU2_S_MODE, check_filament()); break; case 3: // response to mmu commands @@ -327,6 +340,7 @@ void MMU2::mmu_loop() { } state = 1; } + TERN_(PRUSA_MMU2_S_MODE, check_filament()); break; } } @@ -437,6 +451,33 @@ void MMU2::check_version() { } } +static bool mmu2_not_responding() { + LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING); + BUZZ(100, 659); + BUZZ(200, 698); + BUZZ(100, 659); + BUZZ(300, 440); + BUZZ(100, 659); +} + +#if ENABLED(PRUSA_MMU2_S_MODE) + + bool MMU2::load_to_gears() { + command(MMU_CMD_C0); + manage_response(true, true); + LOOP_L_N(i, MMU2_C0_RETRY) { // Keep loading until filament reaches gears + if (mmu2s_triggered) break; + command(MMU_CMD_C0); + manage_response(true, true); + check_filament(); + } + const bool success = mmu2s_triggered && can_load(); + if (!success) mmu2_not_responding(); + return success; + } + +#endif + /** * Handle tool change */ @@ -452,18 +493,15 @@ void MMU2::tool_change(uint8_t index) { ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); command(MMU_CMD_T0 + index); - manage_response(true, true); - command(MMU_CMD_C0); - extruder = index; //filament change is finished - active_extruder = 0; - - ENABLE_AXIS_E0(); - - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); - + if (load_to_gears()) { + extruder = index; // filament change is finished + active_extruder = 0; + ENABLE_AXIS_E0(); + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); + } ui.reset_status(); } @@ -500,12 +538,13 @@ void MMU2::tool_change(const char* special) { DISABLE_AXIS_E0(); command(MMU_CMD_T0 + index); manage_response(true, true); - command(MMU_CMD_C0); - mmu_loop(); - ENABLE_AXIS_E0(); - extruder = index; - active_extruder = 0; + if (load_to_gears()) { + mmu_loop(); + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; + } } break; case 'c': { @@ -579,12 +618,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (turn_off_nozzle) thermalManager.setTargetHotend(0, active_extruder); - LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING); - BUZZ(100, 659); - BUZZ(200, 698); - BUZZ(100, 659); - BUZZ(300, 440); - BUZZ(100, 659); + mmu2_not_responding(); } } else if (mmu_print_saved) { @@ -632,6 +666,39 @@ void MMU2::filament_runout() { planner.synchronize(); } +#if ENABLED(PRUSA_MMU2_S_MODE) + void MMU2::check_filament() { + const bool runout = READ(FIL_RUNOUT_PIN) ^ (FIL_RUNOUT_INVERTING); + if (runout && !mmu2s_triggered) { + DEBUG_ECHOLNPGM("MMU <= 'A'"); + tx_str_P(PSTR("A\n")); + } + mmu2s_triggered = runout; + } + + bool MMU2::can_load() { + execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence)); + + int filament_detected_count = 0; + const int steps = MMU2_CAN_LOAD_RETRACT / MMU2_CAN_LOAD_INCREMENT; + DEBUG_ECHOLNPGM("MMU can_load:"); + LOOP_L_N(i, steps) { + execute_extruder_sequence((const E_Step *)can_load_increment_sequence, COUNT(can_load_increment_sequence)); + check_filament(); // Don't trust the idle function + DEBUG_CHAR(mmu2s_triggered ? 'O' : 'o'); + if (mmu2s_triggered) ++filament_detected_count; + } + + if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION / MMU2_CAN_LOAD_INCREMENT)) { + DEBUG_ECHOLNPGM(" failed."); + return false; + } + + DEBUG_ECHOLNPGM(" succeeded."); + return true; + } +#endif + #if BOTH(HAS_LCD_MENU, MMU2_MENUS) // Load filament into MMU2 @@ -656,20 +723,19 @@ void MMU2::filament_runout() { LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); return false; } - else { - command(MMU_CMD_T0 + index); - manage_response(true, true); - command(MMU_CMD_C0); - mmu_loop(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + + const bool success = load_to_gears(); + if (success) { + mmu_loop(); extruder = index; active_extruder = 0; - load_to_nozzle(); - BUZZ(200, 404); - return true; } + return success; } /** diff --git a/Marlin/src/feature/mmu2/mmu2.h b/Marlin/src/feature/mmu2/mmu2.h index a887644477..8dd07f8847 100644 --- a/Marlin/src/feature/mmu2/mmu2.h +++ b/Marlin/src/feature/mmu2/mmu2.h @@ -80,7 +80,17 @@ private: static void filament_runout(); + #if ENABLED(PRUSA_MMU2_S_MODE) + static bool mmu2s_triggered; + static void check_filament(); + static bool can_load(); + static bool load_to_gears(); + #else + FORCE_INLINE static bool load_to_gears() { return true; } + #endif + static bool enabled, ready, mmu_print_saved; + static uint8_t cmd, cmd_arg, last_cmd, extruder; static int8_t state; static volatile int8_t finda; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 8d4b9d33bd..181ca8b88e 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2740,6 +2740,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "PRUSA_MMU2 requires NOZZLE_PARK_FEATURE." #elif EXTRUDERS != 5 #error "PRUSA_MMU2 requires EXTRUDERS = 5." + #elif ENABLED(PRUSA_MMU2_S_MODE) && DISABLED(FILAMENT_RUNOUT_SENSOR) + #error "PRUSA_MMU2_S_MODE requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." #elif DISABLED(ADVANCED_PAUSE_FEATURE) static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2."); #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 94d9d44cf7..e9cd043e6d 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -528,21 +528,21 @@ namespace Language_en { PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Resume Print"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resuming..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Load Filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Load All"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Load to Nozzle"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Eject Filament"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Eject Filament ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Unload Filament"); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Resume"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Resuming..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Load"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Load All"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Load to Nozzle"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Eject"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Eject ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Unload"); PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Loading Fil. %i..."); PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejecting Fil. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Unloading Fil...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("All"); PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reset MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetting MMU..."); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Resetting..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Remove, click"); PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index 45dbcb9ffb..b17d60ba89 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -71,7 +71,7 @@ opt_set NUM_SERVOS 1 opt_enable ZONESTAR_LCD Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE BOOT_MARLIN_LOGO_ANIMATED \ AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL \ NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ - PRUSA_MMU2 MMU2_MENUS NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING + PRUSA_MMU2 MMU2_MENUS PRUSA_MMU2_S_MODE FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING exec_test $1 $2 "RAMPS | ZONESTAR_LCD | MMU2 | Servo Probe | ABL 3-Pt | Debug Leveling | EEPROM | G38 ..." # From 4ed912eb23744f750bbb4658f0a1822f5397457f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 16:32:08 -0500 Subject: [PATCH 0278/1454] Misc. patches --- Marlin/src/HAL/STM32F1/SPI.cpp | 2 +- Marlin/src/MarlinCore.cpp | 15 ++++--- Marlin/src/core/serial.h | 7 +-- Marlin/src/module/configuration_store.cpp | 54 ++++++++++++----------- 4 files changed, 41 insertions(+), 37 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 8eb8f9aa88..5576cc7b56 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -266,7 +266,7 @@ void SPIClass::endTransaction() { } uint16_t SPIClass::read() { while (!spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ } - return (uint16)spi_rx_reg(_currentSetting->spi_d); + return (uint16_t)spi_rx_reg(_currentSetting->spi_d); } void SPIClass::read(uint8_t *buf, uint32_t len) { diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 47b5f51d2c..6dc76947e5 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -30,6 +30,14 @@ #include "MarlinCore.h" +#include "HAL/shared/Delay.h" +#include "HAL/shared/esp_wifi.h" + +#ifdef ARDUINO + #include +#endif +#include + #include "core/utility.h" #include "lcd/ultralcd.h" #include "module/motion.h" @@ -43,15 +51,8 @@ #include "module/printcounter.h" // PrintCounter or Stopwatch #include "feature/closedloop.h" -#include "HAL/shared/Delay.h" -#include "HAL/shared/esp_wifi.h" - #include "module/stepper/indirection.h" -#ifdef ARDUINO - #include -#endif -#include #include "libs/nozzle.h" #include "gcode/gcode.h" diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 812ff5471f..7050caa1f0 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -245,10 +245,11 @@ extern uint8_t marlin_debug_flags; #define SERIAL_ECHOLIST(pre,V...) do{ SERIAL_ECHOPGM(pre); _SLST_N(NUM_ARGS(V),V); }while(0) #define SERIAL_ECHOLIST_N(N,V...) _SLST_N(N,LIST_N(N,V)) -#define SERIAL_ECHO_P(P) (serialprintPGM(P)) +#define SERIAL_ECHOPGM_P(P) (serialprintPGM(P)) +#define SERIAL_ECHOLNPGM_P(P) (serialprintPGM(P "\n")) -#define SERIAL_ECHOPGM(S) (SERIAL_ECHO_P(PSTR(S))) -#define SERIAL_ECHOLNPGM(S) (SERIAL_ECHO_P(PSTR(S "\n"))) +#define SERIAL_ECHOPGM(S) (serialprintPGM(PSTR(S))) +#define SERIAL_ECHOLNPGM(S) (serialprintPGM(PSTR(S "\n"))) #define SERIAL_ECHOPAIR_F_P(P,V...) do{ serialprintPGM(P); SERIAL_ECHO_F(V); }while(0) #define SERIAL_ECHOLNPAIR_F_P(V...) do{ SERIAL_ECHOPAIR_F_P(V); SERIAL_EOL(); }while(0) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 72336f7cc1..df845c593c 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -3224,31 +3224,33 @@ void MarlinSettings::reset() { #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) say_M906(forReplay); - #if AXIS_IS_TMC(X) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.getMilliamps()); - #endif - #if AXIS_IS_TMC(Y) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.getMilliamps()); - #endif - #if AXIS_IS_TMC(Z) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.getMilliamps()); - #endif - SERIAL_EOL(); + SERIAL_ECHOLNPAIR_P( + #if AXIS_IS_TMC(X) + SP_X_STR, stepperX.getMilliamps(), + #endif + #if AXIS_IS_TMC(Y) + SP_Y_STR, stepperY.getMilliamps(), + #endif + #if AXIS_IS_TMC(Z) + SP_Z_STR, stepperZ.getMilliamps() + #endif + ); #endif #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) say_M906(forReplay); SERIAL_ECHOPGM(" I1"); - #if AXIS_IS_TMC(X2) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.getMilliamps()); - #endif - #if AXIS_IS_TMC(Y2) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.getMilliamps()); - #endif - #if AXIS_IS_TMC(Z2) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.getMilliamps()); - #endif - SERIAL_EOL(); + SERIAL_ECHOLNPAIR_P( + #if AXIS_IS_TMC(X2) + SP_X_STR, stepperX2.getMilliamps(), + #endif + #if AXIS_IS_TMC(Y2) + SP_Y_STR, stepperY2.getMilliamps(), + #endif + #if AXIS_IS_TMC(Z2) + SP_Z_STR, stepperZ2.getMilliamps() + #endif + ); #endif #if AXIS_IS_TMC(Z3) @@ -3451,9 +3453,9 @@ void MarlinSettings::reset() { if (chop_x || chop_y || chop_z) { say_M569(forReplay); - if (chop_x) SERIAL_ECHO_P(SP_X_STR); - if (chop_y) SERIAL_ECHO_P(SP_Y_STR); - if (chop_z) SERIAL_ECHO_P(SP_Z_STR); + if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR); + if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR); + if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR); SERIAL_EOL(); } @@ -3475,9 +3477,9 @@ void MarlinSettings::reset() { if (chop_x2 || chop_y2 || chop_z2) { say_M569(forReplay, PSTR("I1")); - if (chop_x2) SERIAL_ECHO_P(SP_X_STR); - if (chop_y2) SERIAL_ECHO_P(SP_Y_STR); - if (chop_z2) SERIAL_ECHO_P(SP_Z_STR); + if (chop_x2) SERIAL_ECHOPGM_P(SP_X_STR); + if (chop_y2) SERIAL_ECHOPGM_P(SP_Y_STR); + if (chop_z2) SERIAL_ECHOPGM_P(SP_Z_STR); SERIAL_EOL(); } From eebb68cd7f260d02a21e403b528547922203cbae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 26 Apr 2020 03:09:15 -0500 Subject: [PATCH 0279/1454] SPI performance tweak --- Marlin/src/HAL/LPC1768/include/SPI.h | 2 +- Marlin/src/HAL/STM32F1/SPI.cpp | 4 ++-- Marlin/src/HAL/STM32F1/SPI.h | 7 ++++--- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index af085f29a9..3bc0299b14 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -39,7 +39,7 @@ class SPISettings { class SPIClass { public: void begin(); - void beginTransaction(SPISettings); + void beginTransaction(const SPISettings&); void endTransaction() {}; uint8_t transfer(uint8_t data); uint16_t transfer16(uint16_t data); diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 5576cc7b56..991ceb3148 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -243,7 +243,7 @@ void SPIClass::setDataMode(uint8_t dataMode) { _currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA)); } -void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) { +void SPIClass::beginTransaction(uint8_t pin, const SPISettings &settings) { setBitOrder(settings.bitOrder); setDataMode(settings.dataMode); setDataSize(settings.dataSize); @@ -251,7 +251,7 @@ void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) { begin(); } -void SPIClass::beginTransactionSlave(SPISettings settings) { +void SPIClass::beginTransactionSlave(const SPISettings &settings) { setBitOrder(settings.bitOrder); setDataMode(settings.dataMode); setDataSize(settings.dataSize); diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 0162ac13bb..dc2a215865 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -126,6 +126,7 @@ private: bitOrder = inBitOrder; dataMode = inDataMode; dataSize = inDataSize; + //state = SPI_STATE_IDLE; } uint32_t clock; uint32_t dataSize; @@ -187,11 +188,11 @@ public: */ void end(); - void beginTransaction(SPISettings settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); } - void beginTransaction(uint8_t pin, SPISettings settings); + void beginTransaction(const SPISettings &settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); } + void beginTransaction(uint8_t pin, const SPISettings &settings); void endTransaction(); - void beginTransactionSlave(SPISettings settings); + void beginTransactionSlave(const SPISettings &settings); void setClockDivider(uint32_t clockDivider); void setBitOrder(BitOrder bitOrder); From ef74ca60c00422f798abc25ae30eb8f9f43a8dc6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 26 Apr 2020 03:09:31 -0500 Subject: [PATCH 0280/1454] Fix unwarm regData index --- Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp b/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp index d5449f863e..26ca8b2604 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp @@ -807,7 +807,7 @@ UnwResult UnwStartThumb(UnwState * const state) { case 2: /* MOV */ UnwPrintd5("MOV r%d, r%d\t; r%d %s", rhd, rhs, rhd, M_Origin2Str(state->regData[rhs].o)); state->regData[rhd].v = state->regData[rhs].v; - state->regData[rhd].o = state->regData[rhd].o; + state->regData[rhd].o = state->regData[rhs].o; break; case 3: /* BX */ From 3bee705febaac5be7df4984b5eeda79aa4bacb8e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 27 Apr 2020 00:03:28 +0000 Subject: [PATCH 0281/1454] [cron] Bump distribution date (2020-04-27) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 51cf3ef084..1c1a54cd68 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-26" + #define STRING_DISTRIBUTION_DATE "2020-04-27" #endif /** From 8f86f7c601d6951496f1233135b5ebbb767bc461 Mon Sep 17 00:00:00 2001 From: Gurmeet Athwal Date: Mon, 27 Apr 2020 07:25:14 +0530 Subject: [PATCH 0282/1454] Add Cap:SDCARD to M115 (#17208) --- Marlin/src/gcode/host/M115.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 2be95da0c7..144d42ff86 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -96,6 +96,9 @@ void GcodeSuite::M115() { // PROMPT SUPPORT (M876) cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); + // SDCARD (M20, M23, M24, etc.) + cap_line(PSTR("SDCARD"), ENABLED(SDSUPPORT)); + // AUTOREPORT_SD_STATUS (M27 extension) cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); From e1ad955897f8f2fec1a3797ab45453b2581ed5b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 05:06:55 -0500 Subject: [PATCH 0283/1454] Revert EEPROM tweak --- Marlin/src/module/configuration_store.cpp | 40 ++++++++++------------- 1 file changed, 18 insertions(+), 22 deletions(-) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index df845c593c..ea324731c5 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -3224,33 +3224,29 @@ void MarlinSettings::reset() { #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) say_M906(forReplay); - SERIAL_ECHOLNPAIR_P( - #if AXIS_IS_TMC(X) - SP_X_STR, stepperX.getMilliamps(), - #endif - #if AXIS_IS_TMC(Y) - SP_Y_STR, stepperY.getMilliamps(), - #endif - #if AXIS_IS_TMC(Z) - SP_Z_STR, stepperZ.getMilliamps() - #endif - ); + #if AXIS_IS_TMC(X) + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.getMilliamps()); + #endif + #if AXIS_IS_TMC(Y) + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.getMilliamps()); + #endif + #if AXIS_IS_TMC(Z) + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.getMilliamps()); + #endif #endif #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) say_M906(forReplay); SERIAL_ECHOPGM(" I1"); - SERIAL_ECHOLNPAIR_P( - #if AXIS_IS_TMC(X2) - SP_X_STR, stepperX2.getMilliamps(), - #endif - #if AXIS_IS_TMC(Y2) - SP_Y_STR, stepperY2.getMilliamps(), - #endif - #if AXIS_IS_TMC(Z2) - SP_Z_STR, stepperZ2.getMilliamps() - #endif - ); + #if AXIS_IS_TMC(X2) + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.getMilliamps()); + #endif + #if AXIS_IS_TMC(Y2) + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.getMilliamps()); + #endif + #if AXIS_IS_TMC(Z2) + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.getMilliamps()); + #endif #endif #if AXIS_IS_TMC(Z3) From 011ecc341ae3908ab383130331b535611e661866 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 04:33:59 -0500 Subject: [PATCH 0284/1454] Fix I2C_ADDRESS ambiguity --- Marlin/src/core/macros.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 765f157e2f..214539d830 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -292,7 +292,7 @@ #define FMOD(x, y) fmodf(x, y) #define HYPOT(x,y) SQRT(HYPOT2(x,y)) -#define I2C_ADDRESS(A) (TERN(TARGET_LPC1768, (A) << 1, A)) +#define I2C_ADDRESS(A) int(TERN(TARGET_LPC1768, (A) << 1, A)) // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT From 3d45a4bd232c83450c269bb3f0fefa6fc67c788d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 04:35:20 -0500 Subject: [PATCH 0285/1454] Encapsulate Temperature items --- Marlin/src/lcd/extui/ui_api.cpp | 2 -- Marlin/src/lcd/menu/menu.h | 4 --- Marlin/src/lcd/menu/menu_temperature.cpp | 32 ++++++++++++++---------- Marlin/src/module/temperature.cpp | 21 ++++++---------- Marlin/src/module/temperature.h | 5 ++++ 5 files changed, 31 insertions(+), 33 deletions(-) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 0e33dc5835..7a1c0fb251 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -945,7 +945,6 @@ namespace ExtUI { #endif { #if HAS_HOTEND - static constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); const int16_t e = heater - H0; thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e); #endif @@ -957,7 +956,6 @@ namespace ExtUI { value *= TOUCH_UI_LCD_TEMP_SCALING; #endif #if HAS_HOTEND - constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); const int16_t e = extruder - E0; enableHeater(extruder); thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e); diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 5f3e6d965a..ca475a115e 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -29,10 +29,6 @@ extern int8_t encoderLine, encoderTopLine, screen_items; -#if HAS_HOTEND - constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); -#endif - void scroll_screen(const uint8_t limit, const bool is_menu); bool printer_busy(); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 921fa91668..25c9125c27 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -47,21 +47,27 @@ uint8_t MarlinUI::preheat_fan_speed[2]; // "Temperature" submenu items // -void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const uint8_t fan) { + +void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb) { #if HAS_HOTEND - if (temph > 0) thermalManager.setTargetHotend(_MIN(heater_maxtemp[endnum] - 15, temph), endnum); + if (indh >= 0 && ui.preheat_hotend_temp[indh] > 0) + setTargetHotend(_MIN(heater_maxtemp[e] - 15, ui.preheat_hotend_temp[indh]), e); + #else + UNUSED(temph); #endif #if HAS_HEATED_BED - if (tempb >= 0) thermalManager.setTargetBed(tempb); + if (indb >= 0 && ui.preheat_bed_temp[indb] >= 0) setTargetBed(ui.preheat_bed_temp[indb]); #else - UNUSED(tempb); + UNUSED(indb); #endif - #if FAN_COUNT > 0 - #if FAN_COUNT > 1 - thermalManager.set_fan_speed(active_extruder < FAN_COUNT ? active_extruder : 0, fan); - #else - thermalManager.set_fan_speed(0, fan); - #endif + #if HAS_FAN + set_fan_speed(( + #if FAN_COUNT > 1 + active_extruder < FAN_COUNT ? active_extruder : 0 + #else + 0 + #endif + ), fan); #else UNUSED(fan); #endif @@ -70,17 +76,17 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #if HAS_TEMP_HOTEND inline void _preheat_end(const uint8_t m, const uint8_t e) { - _lcd_preheat(e, ui.preheat_hotend_temp[m], -1, ui.preheat_fan_speed[m]); + thermalManager.lcd_preheat(e, m, -1); } #if HAS_HEATED_BED inline void _preheat_both(const uint8_t m, const uint8_t e) { - _lcd_preheat(e, ui.preheat_hotend_temp[m], ui.preheat_bed_temp[m], ui.preheat_fan_speed[m]); + thermalManager.lcd_preheat(e, m, m); } #endif #endif #if HAS_HEATED_BED inline void _preheat_bed(const uint8_t m) { - _lcd_preheat(0, 0, ui.preheat_bed_temp[m], ui.preheat_fan_speed[m]); + thermalManager.lcd_preheat(-1, -1, m); } #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index fc86061ccc..3b11dcba57 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -28,9 +28,10 @@ #include "endstops.h" #include "../MarlinCore.h" -#include "../lcd/ultralcd.h" #include "planner.h" #include "../HAL/shared/Delay.h" + +#include "../lcd/ultralcd.h" #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" #endif @@ -2241,22 +2242,14 @@ void Temperature::readings_ready() { #if HAS_HOTEND static constexpr int8_t temp_dir[] = { - #if ENABLED(HEATER_0_USES_MAX6675) - 0 - #else - TEMPDIR(0) - #endif + TERN(HEATER_0_USES_MAX6675, 0, TEMPDIR(0)) #if HAS_MULTI_HOTEND - #define _TEMPDIR(N) , TEMPDIR(N) - #if ENABLED(HEATER_1_USES_MAX6675) - , 0 - #else - _TEMPDIR(1) - #endif + , TERN(HEATER_1_USES_MAX6675, 0, TEMPDIR(1)) #if HOTENDS > 2 + #define _TEMPDIR(N) , TEMPDIR(N) REPEAT_S(2, HOTENDS, _TEMPDIR) - #endif // HOTENDS > 2 - #endif // HAS_MULTI_HOTEND + #endif + #endif }; LOOP_L_N(e, COUNT(temp_dir)) { diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index f9f2fbc071..c08f4dc754 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -322,6 +322,7 @@ class Temperature { #if HAS_HOTEND #define HOTEND_TEMPS (HOTENDS + ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)) static hotend_info_t temp_hotend[HOTEND_TEMPS]; + static constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); #endif TERN_(HAS_HEATED_BED, static bed_info_t temp_bed); TERN_(HAS_TEMP_PROBE, static probe_info_t temp_probe); @@ -779,6 +780,10 @@ class Temperature { TERN_(HAS_DISPLAY, static void set_heating_message(const uint8_t e)); + #if HAS_LCD_MENU + static void lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb); + #endif + private: static void update_raw_temperatures(); static void updateTemperaturesFromRawValues(); From 8b3c7dda755ebce5bd57a7ce52891a137ea12b35 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 04:41:18 -0500 Subject: [PATCH 0286/1454] Add HAS_FAN and others --- Marlin/src/feature/pause.cpp | 4 +-- Marlin/src/feature/powerloss.cpp | 4 +-- Marlin/src/feature/powerloss.h | 2 +- Marlin/src/feature/probe_temp_comp.h | 2 +- Marlin/src/gcode/bedlevel/G26.cpp | 4 +-- Marlin/src/gcode/calibrate/G76_M871.cpp | 2 +- Marlin/src/gcode/config/M217.cpp | 2 +- Marlin/src/gcode/control/M42.cpp | 4 +-- Marlin/src/gcode/control/M80_M81.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- Marlin/src/gcode/temp/M106_M107.cpp | 4 +-- Marlin/src/inc/Conditionals_LCD.h | 2 ++ Marlin/src/inc/Conditionals_post.h | 2 ++ Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 4 +-- Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 4 +-- Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h | 4 +-- .../extui/lib/dgus/fysetc/DGUSDisplayDef.cpp | 8 ++--- .../extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp | 10 +++--- .../extui/lib/dgus/origin/DGUSDisplayDef.cpp | 4 +-- .../screens/temperature_screen.cpp | 6 ++-- Marlin/src/lcd/extui/ui_api.cpp | 8 ++--- Marlin/src/lcd/menu/menu.h | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 2 +- Marlin/src/lcd/menu/menu_temperature.cpp | 31 +++++++------------ Marlin/src/lcd/menu/menu_tune.cpp | 6 ++-- Marlin/src/lcd/menu/menu_ubl.cpp | 4 +-- Marlin/src/module/planner.cpp | 14 ++++----- Marlin/src/module/planner.h | 2 +- Marlin/src/module/temperature.cpp | 6 ++-- Marlin/src/module/temperature.h | 8 ++--- Marlin/src/module/tool_change.cpp | 8 ++--- Marlin/src/module/tool_change.h | 2 +- 35 files changed, 85 insertions(+), 90 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 4b50d3df26..396819324c 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -402,7 +402,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float // Wait for buffered blocks to complete planner.synchronize(); - #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && FAN_COUNT > 0 + #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN thermalManager.set_fans_paused(true); #endif @@ -621,7 +621,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le if (did_pause_print) { card.startFileprint(); --did_pause_print; } #endif - #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && FAN_COUNT > 0 + #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN thermalManager.set_fans_paused(false); #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index ccb85049d8..02a97e3436 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -195,7 +195,7 @@ void PrintJobRecovery::save(const bool force/*=false*/) { TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.temp_bed.target); - #if FAN_COUNT + #if HAS_FAN COPY(info.fan_speed, thermalManager.fan_speed); #endif @@ -508,7 +508,7 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed); #endif - #if FAN_COUNT + #if HAS_FAN DEBUG_ECHOPGM("fan_speed: "); FANS_LOOP(i) { DEBUG_ECHO(int(info.fan_speed[i])); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 34a26b6eb9..71f9861e87 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -76,7 +76,7 @@ typedef struct { int16_t target_temperature_bed; #endif - #if FAN_COUNT + #if HAS_FAN uint8_t fan_speed[FAN_COUNT]; #endif diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 4ce7066c15..5ae4175104 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -65,7 +65,7 @@ class ProbeTempComp { static constexpr xy_pos_t measure_point = PTC_PROBE_POS; // Coordinates to probe //measure_point = { 12.0f, 7.3f }; // Coordinates for the MK52 magnetic heatbed - static constexpr int probe_calib_bed_temp = BED_MAXTEMP - 10, // Bed temperature while calibrating probe + static constexpr int probe_calib_bed_temp = BED_MAX_TARGET, // Bed temperature while calibrating probe bed_calib_probe_temp = 30; // Probe temperature while calibrating bed static int16_t *sensor_z_offsets[TSI_COUNT], diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 9f3833803a..355f1ffa1c 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -511,8 +511,8 @@ void GcodeSuite::G26() { #if HAS_HEATED_BED if (parser.seenval('B')) { g26_bed_temp = parser.value_celsius(); - if (g26_bed_temp && !WITHIN(g26_bed_temp, 40, (BED_MAXTEMP - 10))) { - SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", int(BED_MAXTEMP - 10), "C)."); + if (g26_bed_temp && !WITHIN(g26_bed_temp, 40, BED_MAX_TARGET)) { + SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", int(BED_MAX_TARGET), "C)."); return; } } diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 02895c7e05..adabf22344 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -201,7 +201,7 @@ void GcodeSuite::G76() { report_temps(next_temp_report); const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz); - if (isnan(measured_z) || target_bed > BED_MAXTEMP - 10) break; + if (isnan(measured_z) || target_bed > BED_MAX_TARGET) break; } SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 6e8c899fb0..a1e53e5ecb 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -115,7 +115,7 @@ void GcodeSuite::M217() { if (parser.seenval('P')) { const int16_t v = parser.value_linear_units(); toolchange_settings.prime_speed = constrain(v, 10, 5400); } if (parser.seenval('R')) { const int16_t v = parser.value_linear_units(); toolchange_settings.retract_speed = constrain(v, 10, 5400); } if (parser.seenval('U')) { const int16_t v = parser.value_linear_units(); toolchange_settings.unretract_speed = constrain(v, 10, 5400); } - #if TOOLCHANGE_FS_FAN >= 0 && FAN_COUNT > 0 + #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN if (parser.seenval('F')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_speed = constrain(v, 0, 255); } if (parser.seenval('G')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_time = constrain(v, 1, 30); } #endif diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 74625b0318..4b2b7fc0f7 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -24,7 +24,7 @@ #include "../../MarlinCore.h" // for pin_is_protected #include "../../inc/MarlinConfig.h" -#if FAN_COUNT > 0 +#if HAS_FAN #include "../../module/temperature.h" #endif @@ -64,7 +64,7 @@ void GcodeSuite::M42() { if (!parser.seenval('S')) return; const byte pin_status = parser.value_byte(); - #if FAN_COUNT > 0 + #if HAS_FAN switch (pin) { #if HAS_FAN0 case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; return; diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index a5ff7d05d9..6ba0949027 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -92,7 +92,7 @@ void GcodeSuite::M81() { print_job_timer.stop(); planner.finish_and_disable(); - #if FAN_COUNT > 0 + #if HAS_FAN thermalManager.zero_fan_speeds(); #if ENABLED(PROBING_FANS_OFF) thermalManager.fans_paused = false; diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 8bebeb1c15..a6f54ee022 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -467,7 +467,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 105: M105(); return; // M105: Report Temperatures (and say "ok") - #if FAN_COUNT > 0 + #if HAS_FAN case 106: M106(); break; // M106: Fan On case 107: M107(); break; // M107: Fan Off #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index a3d37262f2..6a4a7af985 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -554,7 +554,7 @@ private: static void M105(); - #if FAN_COUNT > 0 + #if HAS_FAN static void M106(); static void M107(); #endif diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index 3116727533..a66c62e8af 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -52,7 +52,7 @@ void GcodeSuite::M145() { #if TEMP_SENSOR_BED != 0 if (parser.seenval('B')) { v = parser.value_int(); - ui.preheat_bed_temp[material] = constrain(v, BED_MINTEMP, BED_MAXTEMP - 10); + ui.preheat_bed_temp[material] = constrain(v, BED_MINTEMP, BED_MAX_TARGET); } #endif } diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index 2415484d51..7fbc53297e 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if FAN_COUNT > 0 +#if HAS_FAN #include "../gcode.h" #include "../../module/motion.h" @@ -74,4 +74,4 @@ void GcodeSuite::M107() { thermalManager.set_fan_speed(p, 0); } -#endif // FAN_COUNT > 0 +#endif // HAS_FAN diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 14aa031ac6..9558c314d1 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -408,6 +408,8 @@ */ #if EXTRUDERS == 0 + #undef EXTRUDERS + #define EXTRUDERS 0 #undef DISTINCT_E_FACTORS #undef SINGLENOZZLE #undef SWITCHING_EXTRUDER diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 67116f662c..b4f68fcf7b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1707,6 +1707,7 @@ // Shorthand for common combinations #if HAS_TEMP_BED && HAS_HEATER_BED #define HAS_HEATED_BED 1 + #define BED_MAX_TARGET (BED_MAXTEMP - 10) #endif #if HAS_HEATED_BED || HAS_TEMP_CHAMBER #define BED_OR_CHAMBER 1 @@ -2084,6 +2085,7 @@ #endif #if FAN_COUNT > 0 + #define HAS_FAN 1 #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ FAN_INVERTING) #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 181ca8b88e..8e37362971 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -262,7 +262,7 @@ #error "LCD_PIN_RESET is now LCD_RESET_PIN. Please update your pins definitions." #elif defined(EXTRUDER_0_AUTO_FAN_PIN) || defined(EXTRUDER_1_AUTO_FAN_PIN) || defined(EXTRUDER_2_AUTO_FAN_PIN) || defined(EXTRUDER_3_AUTO_FAN_PIN) #error "EXTRUDER_[0123]_AUTO_FAN_PIN is now E[0123]_AUTO_FAN_PIN. Please update your Configuration_adv.h." -#elif defined(PID_FAN_SCALING) && FAN_COUNT <= 0 +#elif defined(PID_FAN_SCALING) && !HAS_FAN #error "PID_FAN_SCALING needs at least one fan enabled." #elif defined(min_software_endstops) || defined(max_software_endstops) #error "(min|max)_software_endstops are now (MIN|MAX)_SOFTWARE_ENDSTOPS. Please update your configuration." diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index ff76741ce7..18befefc13 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -1072,7 +1072,7 @@ void MarlinUI::draw_status_screen() { if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) leds |= LED_A; if (TERN0(HAS_HOTEND, thermalManager.degTargetHotend(0) > 0)) leds |= LED_B; - #if FAN_COUNT > 0 + #if HAS_FAN if ( TERN0(HAS_FAN0, thermalManager.fan_speed[0]) || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) || TERN0(HAS_FAN2, thermalManager.fan_speed[2]) @@ -1082,7 +1082,7 @@ void MarlinUI::draw_status_screen() { || TERN0(HAS_FAN6, thermalManager.fan_speed[6]) || TERN0(HAS_FAN7, thermalManager.fan_speed[7]) ) leds |= LED_C; - #endif // FAN_COUNT > 0 + #endif // HAS_FAN if (TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1) > 0)) leds |= LED_C; diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index 91acd0a360..ccaef782a6 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -277,7 +277,7 @@ void DGUSScreenVariableHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable #endif // Send fan status value to the display. -#if FAN_COUNT > 0 +#if HAS_FAN void DGUSScreenVariableHandler::DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { DEBUG_ECHOPAIR(" DGUSLCD_SendFanStatusToDisplay ", var.VP); @@ -872,7 +872,7 @@ void DGUSScreenVariableHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, } #endif -#if FAN_COUNT +#if HAS_FAN void DGUSScreenVariableHandler::HandleFanControl(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("HandleFanControl"); *(uint8_t*)var.memadr = *(uint8_t*)var.memadr > 0 ? 0 : 255; diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h index 00e626adc9..9eddfcf3b5 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h @@ -151,7 +151,7 @@ public: // Hook for live z adjust action static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); #endif - #if FAN_COUNT > 0 + #if HAS_FAN // Hook for fan control static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); #endif @@ -221,7 +221,7 @@ public: static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); #endif - #if FAN_COUNT > 0 + #if HAS_FAN static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); #endif static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp index 4a51606314..b9f7c8543d 100644 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp @@ -56,7 +56,7 @@ const uint16_t VPList_Main[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, VP_FAN0_STATUS, #endif VP_XPos, VP_YPos, VP_ZPos, @@ -92,7 +92,7 @@ const uint16_t VPList_Status[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, #endif VP_XPos, VP_YPos, VP_ZPos, @@ -192,7 +192,7 @@ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, #if FAN_COUNT > 1 VP_Fan1_Percentage, @@ -410,7 +410,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Fan Data - #if FAN_COUNT + #if HAS_FAN #define FAN_VPHELPER(N) \ VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], DGUSScreenVariableHandler::DGUSLCD_PercentageToUint8, &DGUSScreenVariableHandler::DGUSLCD_SendPercentageToDisplay), \ VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &DGUSScreenVariableHandler::HandleFanControl, nullptr), \ diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp index b641ec9ec7..ab5b453855 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp @@ -56,7 +56,7 @@ const uint16_t VPList_Main[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, VP_FAN0_STATUS, #endif VP_XPos, VP_YPos, VP_ZPos, @@ -92,7 +92,7 @@ const uint16_t VPList_Status[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, #endif VP_XPos, VP_YPos, VP_ZPos, @@ -191,7 +191,7 @@ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, #if FAN_COUNT > 1 VP_Fan1_Percentage, @@ -212,7 +212,7 @@ const uint16_t VPList_SDPrintTune[] PROGMEM = { VP_T_Bed_Is, VP_T_Bed_Set, #endif VP_Feedrate_Percentage, - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, #endif VP_Flowrate_E0, @@ -409,7 +409,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Fan Data - #if FAN_COUNT + #if HAS_FAN #define FAN_VPHELPER(N) \ VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], DGUSScreenVariableHandler::DGUSLCD_PercentageToUint8, &DGUSScreenVariableHandler::DGUSLCD_SendPercentageToDisplay), \ VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &DGUSScreenVariableHandler::HandleFanControl, nullptr), \ diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp index 81e8a32a7f..b6a7fca903 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp @@ -73,7 +73,7 @@ const uint16_t VPList_Status[] PROGMEM = { #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, #endif - #if FAN_COUNT > 0 + #if HAS_FAN VP_Fan0_Percentage, #endif VP_XPos, VP_YPos, VP_ZPos, @@ -233,7 +233,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Fan Data - #if FAN_COUNT + #if HAS_FAN #define FAN_VPHELPER(N) \ VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], DGUSScreenVariableHandler::DGUSLCD_PercentageToUint8, &DGUSScreenVariableHandler::DGUSLCD_SendPercentageToDisplay), \ VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &DGUSScreenVariableHandler::HandleFanControl, nullptr), \ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp index c647812a0a..5f8a74b0b0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp @@ -60,7 +60,7 @@ void TemperatureScreen::onRedraw(draw_mode_t what) { #if HAS_HEATED_CHAMBER w.adjuster( 22, GET_TEXT_F(MSG_CHAMBER), getTargetTemp_celsius(CHAMBER)); #endif - #if FAN_COUNT > 0 + #if HAS_FAN w.color(fan_speed).units(GET_TEXT_F(MSG_UNITS_PERCENT)); w.adjuster( 10, GET_TEXT_F(MSG_FAN_SPEED), getTargetFan_percent(FAN0)); #endif @@ -90,7 +90,7 @@ bool TemperatureScreen::onTouchHeld(uint8_t tag) { case 8: UI_DECREMENT(TargetTemp_celsius, E3); break; case 9: UI_INCREMENT(TargetTemp_celsius, E3); break; #endif - #if FAN_COUNT > 0 + #if HAS_FAN case 10: UI_DECREMENT(TargetFan_percent, FAN0); break; case 11: UI_INCREMENT(TargetFan_percent, FAN0); break; #endif @@ -99,7 +99,7 @@ bool TemperatureScreen::onTouchHeld(uint8_t tag) { REPEAT(HOTENDS, _HOTEND_OFF); TERN_(HAS_HEATED_BED, setTargetTemp_celsius(0,BED)); TERN_(HAS_HEATED_CHAMBER, setTargetTemp_celsius(0,CHAMBER)); - #if FAN_COUNT > 0 + #if HAS_FAN setTargetFan_percent(0,FAN0); #endif break; diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 7a1c0fb251..fe2d680994 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -293,7 +293,7 @@ namespace ExtUI { } float getTargetFan_percent(const fan_t fan) { - #if FAN_COUNT > 0 + #if HAS_FAN return thermalManager.fanPercent(thermalManager.fan_speed[fan - FAN0]); #else UNUSED(fan); @@ -302,7 +302,7 @@ namespace ExtUI { } float getActualFan_percent(const fan_t fan) { - #if FAN_COUNT > 0 + #if HAS_FAN return thermalManager.fanPercent(thermalManager.scaledFanSpeed(fan - FAN0)); #else UNUSED(fan); @@ -940,7 +940,7 @@ namespace ExtUI { #endif #if HAS_HEATED_BED if (heater == BED) - thermalManager.setTargetBed(LROUND(constrain(value, 0, BED_MAXTEMP - 10))); + thermalManager.setTargetBed(LROUND(constrain(value, 0, BED_MAX_TARGET))); else #endif { @@ -963,7 +963,7 @@ namespace ExtUI { } void setTargetFan_percent(const float value, const fan_t fan) { - #if FAN_COUNT > 0 + #if HAS_FAN if (fan < FAN_COUNT) thermalManager.set_fan_speed(fan - FAN0, map(constrain(value, 0, 100), 0, 100, 0, 255)); #else diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index ca475a115e..824b340377 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -522,7 +522,7 @@ void menu_move(); #endif // First Fan Speed title in "Tune" and "Control>Temperature" menus -#if FAN_COUNT > 0 && HAS_FAN0 +#if HAS_FAN && HAS_FAN0 #if FAN_COUNT > 1 #define FAN_SPEED_1_SUFFIX " 1" #else diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index cb7360d09b..e5ad0f9cbf 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -334,7 +334,7 @@ void menu_advanced_settings(); EDIT_ITEM(int3, MSG_NOZZLE, &ui.preheat_hotend_temp[material], MINTEMP_ALL, MAXTEMP_ALL - 15); #endif #if HAS_HEATED_BED - EDIT_ITEM(int3, MSG_BED, &ui.preheat_bed_temp[material], BED_MINTEMP, BED_MAXTEMP - 10); + EDIT_ITEM(int3, MSG_BED, &ui.preheat_bed_temp[material], BED_MINTEMP, BED_MAX_TARGET); #endif #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 25c9125c27..1e610ec190 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -47,47 +47,38 @@ uint8_t MarlinUI::preheat_fan_speed[2]; // "Temperature" submenu items // - void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb) { #if HAS_HOTEND if (indh >= 0 && ui.preheat_hotend_temp[indh] > 0) setTargetHotend(_MIN(heater_maxtemp[e] - 15, ui.preheat_hotend_temp[indh]), e); #else + UNUSED(e); UNUSED(temph); #endif #if HAS_HEATED_BED - if (indb >= 0 && ui.preheat_bed_temp[indb] >= 0) setTargetBed(ui.preheat_bed_temp[indb]); + if (indb >= 0 && ui.preheat_bed_temp[indb] > 0) setTargetBed(ui.preheat_bed_temp[indb]); #else UNUSED(indb); #endif #if HAS_FAN set_fan_speed(( #if FAN_COUNT > 1 - active_extruder < FAN_COUNT ? active_extruder : 0 - #else - 0 + active_extruder < FAN_COUNT ? active_extruder : #endif - ), fan); - #else - UNUSED(fan); + 0), ui.preheat_fan_speed[m] + ); #endif ui.return_to_status(); } #if HAS_TEMP_HOTEND - inline void _preheat_end(const uint8_t m, const uint8_t e) { - thermalManager.lcd_preheat(e, m, -1); - } + inline void _preheat_end(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, -1); } #if HAS_HEATED_BED - inline void _preheat_both(const uint8_t m, const uint8_t e) { - thermalManager.lcd_preheat(e, m, m); - } + inline void _preheat_both(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, m); } #endif #endif #if HAS_HEATED_BED - inline void _preheat_bed(const uint8_t m) { - thermalManager.lcd_preheat(-1, -1, m); - } + inline void _preheat_bed(const uint8_t m) { thermalManager.lcd_preheat(-1, -1, m); } #endif #if HAS_TEMP_HOTEND || HAS_HEATED_BED @@ -186,7 +177,7 @@ void menu_temperature() { // Bed: // #if HAS_HEATED_BED - EDIT_ITEM_FAST(int3, MSG_BED, &thermalManager.temp_bed.target, 0, BED_MAXTEMP - 10, thermalManager.start_watching_bed); + EDIT_ITEM_FAST(int3, MSG_BED, &thermalManager.temp_bed.target, 0, BED_MAX_TARGET, thermalManager.start_watching_bed); #endif // @@ -199,7 +190,7 @@ void menu_temperature() { // // Fan Speed: // - #if FAN_COUNT > 0 + #if HAS_FAN auto on_fan_update = []{ thermalManager.set_fan_speed(MenuItemBase::itemIndex, editable.uint8); @@ -266,7 +257,7 @@ void menu_temperature() { singlenozzle_item(1); #endif - #endif // FAN_COUNT > 0 + #endif // HAS_FAN #if HAS_TEMP_HOTEND diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 2f4c751775..4ef7e48fa3 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -132,13 +132,13 @@ void menu_tune() { // Bed: // #if HAS_HEATED_BED - EDIT_ITEM_FAST(int3, MSG_BED, &thermalManager.temp_bed.target, 0, BED_MAXTEMP - 10, thermalManager.start_watching_bed); + EDIT_ITEM_FAST(int3, MSG_BED, &thermalManager.temp_bed.target, 0, BED_MAX_TARGET, thermalManager.start_watching_bed); #endif // // Fan Speed: // - #if FAN_COUNT > 0 + #if HAS_FAN auto on_fan_update = []{ thermalManager.set_fan_speed(MenuItemBase::itemIndex, editable.uint8); @@ -205,7 +205,7 @@ void menu_tune() { singlenozzle_item(1); #endif - #endif // FAN_COUNT > 0 + #endif // HAS_FAN // // Flow: diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 31459cf215..dde17b0192 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -128,9 +128,9 @@ void _lcd_ubl_build_custom_mesh() { void _lcd_ubl_custom_mesh() { START_MENU(); BACK_ITEM(MSG_UBL_BUILD_MESH_MENU); - EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); + EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 15)); #if HAS_HEATED_BED - EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP, (BED_MAXTEMP - 10)); + EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP, BED_MAX_TARGET); #endif ACTION_ITEM(MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); END_MENU(); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index b7dc639246..0643ba1cb3 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1264,7 +1264,7 @@ void Planner::check_axes_activity() { xyze_bool_t axis_active = { false }; #endif - #if FAN_COUNT > 0 + #if HAS_FAN uint8_t tail_fan_speed[FAN_COUNT]; #endif @@ -1279,11 +1279,11 @@ void Planner::check_axes_activity() { if (has_blocks_queued()) { - #if FAN_COUNT > 0 || ENABLED(BARICUDA) + #if HAS_FAN || ENABLED(BARICUDA) block_t *block = &block_buffer[block_buffer_tail]; #endif - #if FAN_COUNT > 0 + #if HAS_FAN FANS_LOOP(i) tail_fan_speed[i] = thermalManager.scaledFanSpeed(i, block->fan_speed[i]); #endif @@ -1304,7 +1304,7 @@ void Planner::check_axes_activity() { TERN_(HAS_CUTTER, cutter.refresh()); - #if FAN_COUNT > 0 + #if HAS_FAN FANS_LOOP(i) tail_fan_speed[i] = thermalManager.scaledFanSpeed(i); #endif @@ -1326,7 +1326,7 @@ void Planner::check_axes_activity() { // // Update Fan speeds // - #if FAN_COUNT > 0 + #if HAS_FAN #if FAN_KICKSTART_TIME > 0 static millis_t fan_kick_end[FAN_COUNT] = { 0 }; @@ -1366,7 +1366,7 @@ void Planner::check_axes_activity() { TERN_(HAS_FAN5, FAN_SET(5)); TERN_(HAS_FAN6, FAN_SET(6)); TERN_(HAS_FAN7, FAN_SET(7)); - #endif // FAN_COUNT > 0 + #endif // HAS_FAN TERN_(AUTOTEMP, getHighESpeed()); @@ -1906,7 +1906,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(HAS_CUTTER, block->cutter_power = cutter.power); - #if FAN_COUNT > 0 + #if HAS_FAN FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 8b6cdcada0..bf585320de 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -175,7 +175,7 @@ typedef struct block_t { cutter_power_t cutter_power; // Power level for Spindle, Laser, etc. #endif - #if FAN_COUNT > 0 + #if HAS_FAN uint8_t fan_speed[FAN_COUNT]; #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 3b11dcba57..44de7cc40c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -152,7 +152,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, uint8_t Temperature::chamberfan_speed; // = 0 #endif -#if FAN_COUNT > 0 +#if HAS_FAN uint8_t Temperature::fan_speed[FAN_COUNT]; // = { 0 } @@ -219,7 +219,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #endif -#endif // FAN_COUNT > 0 +#endif // HAS_FAN #if WATCH_HOTENDS hotend_watch_t Temperature::watch_hotend[HOTENDS]; // = { { 0 } } @@ -400,7 +400,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); - if (target > GHV(BED_MAXTEMP - 10, temp_range[heater].maxtemp - 15)) { + if (target > GHV(BED_MAX_TARGET, temp_range[heater].maxtemp - 15)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); return; diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index c08f4dc754..b4cba62b10 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -477,7 +477,7 @@ class Temperature { static float analog_to_celsius_chamber(const int raw); #endif - #if FAN_COUNT > 0 + #if HAS_FAN static uint8_t fan_speed[FAN_COUNT]; #define FANS_LOOP(I) LOOP_L_N(I, FAN_COUNT) @@ -517,10 +517,10 @@ class Temperature { void set_fans_paused(const bool p); #endif - #endif // FAN_COUNT > 0 + #endif // HAS_FAN static inline void zero_fan_speeds() { - #if FAN_COUNT > 0 + #if HAS_FAN FANS_LOOP(i) set_fan_speed(i, 0); #endif } @@ -634,7 +634,7 @@ class Temperature { TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); temp_bed.target = #ifdef BED_MAXTEMP - _MIN(celsius, BED_MAXTEMP - 10) + _MIN(celsius, BED_MAX_TARGET) #else celsius #endif diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index d7f6ef15cc..c1060c1233 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -49,7 +49,7 @@ #if ENABLED(SINGLENOZZLE) uint16_t singlenozzle_temp[EXTRUDERS]; - #if FAN_COUNT > 0 + #if HAS_FAN uint8_t singlenozzle_fan_speed[EXTRUDERS]; #endif #endif @@ -819,7 +819,7 @@ void tool_change_prime() { #endif // Cool down with fan - #if TOOLCHANGE_FS_FAN >= 0 && FAN_COUNT > 0 + #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; safe_delay(toolchange_settings.fan_time * 1000); @@ -1060,7 +1060,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (should_move) { #if ENABLED(SINGLENOZZLE) - #if FAN_COUNT > 0 + #if HAS_FAN singlenozzle_fan_speed[old_tool] = thermalManager.fan_speed[0]; thermalManager.fan_speed[0] = singlenozzle_fan_speed[new_tool]; #endif @@ -1098,7 +1098,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // Cool down with fan - #if TOOLCHANGE_FS_FAN >= 0 && FAN_COUNT > 0 + #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; safe_delay(toolchange_settings.fan_time * 1000); diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 534a17e946..7e73bd7bb2 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -110,7 +110,7 @@ #if ENABLED(SINGLENOZZLE) extern uint16_t singlenozzle_temp[EXTRUDERS]; - #if FAN_COUNT > 0 + #if HAS_FAN extern uint8_t singlenozzle_fan_speed[EXTRUDERS]; #endif #endif From 33217b0dd0e2117905813e3a45632fdc9c66d04f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 04:48:11 -0500 Subject: [PATCH 0287/1454] Add HOTEND_OVERSHOOT --- Marlin/src/gcode/bedlevel/G26.cpp | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 5 ++++- Marlin/src/lcd/extui/ui_api.cpp | 4 ++-- Marlin/src/lcd/menu/menu_advanced.cpp | 6 +++--- Marlin/src/lcd/menu/menu_configuration.cpp | 2 +- Marlin/src/lcd/menu/menu_filament.cpp | 2 +- Marlin/src/lcd/menu/menu_temperature.cpp | 8 ++++---- Marlin/src/lcd/menu/menu_tune.cpp | 6 +++--- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- Marlin/src/module/temperature.h | 2 +- 12 files changed, 23 insertions(+), 20 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 355f1ffa1c..9f94c2d9f0 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -582,7 +582,7 @@ void GcodeSuite::G26() { if (parser.seenval('H')) { g26_hotend_temp = parser.value_celsius(); - if (!WITHIN(g26_hotend_temp, 165, (HEATER_0_MAXTEMP - 15))) { + if (!WITHIN(g26_hotend_temp, 165, (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT))) { SERIAL_ECHOLNPGM("?Specified nozzle temperature not plausible."); return; } diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index a66c62e8af..feac437c6c 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -43,7 +43,7 @@ void GcodeSuite::M145() { int v; if (parser.seenval('H')) { v = parser.value_int(); - ui.preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15); + ui.preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); } if (parser.seenval('F')) { v = parser.value_int(); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 9558c314d1..c47899b34c 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -472,7 +472,10 @@ #if HOTENDS #define HAS_HOTEND 1 - #if HOTENDS > 1 + #ifndef HOTEND_OVERSHOOT + #define HOTEND_OVERSHOOT 15 + #endif + #if HOTENDS_ > 1 #define HAS_MULTI_HOTEND 1 #define HAS_HOTEND_OFFSET 1 #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index fe2d680994..4d6815d638 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -946,7 +946,7 @@ namespace ExtUI { { #if HAS_HOTEND const int16_t e = heater - H0; - thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e); + thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); #endif } } @@ -958,7 +958,7 @@ namespace ExtUI { #if HAS_HOTEND const int16_t e = extruder - E0; enableHeater(extruder); - thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e); + thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); #endif } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 1aedee4757..166442079d 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -257,8 +257,8 @@ void menu_cancelobject(); // #if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) EDIT_ITEM(bool, MSG_AUTOTEMP, &planner.autotemp_enabled); - EDIT_ITEM(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - 15); - EDIT_ITEM(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - 15); + EDIT_ITEM(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - HOTEND_OVERSHOOT); + EDIT_ITEM(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - HOTEND_OVERSHOOT); EDIT_ITEM(float42_52, MSG_FACTOR, &planner.autotemp_factor, 0, 10); #endif @@ -304,7 +304,7 @@ void menu_cancelobject(); #if ENABLED(PID_AUTOTUNE_MENU) #define PID_EDIT_MENU_ITEMS(N) \ _PID_EDIT_MENU_ITEMS(N); \ - EDIT_ITEM_FAST_N(int3, N, MSG_PID_AUTOTUNE_E, &autotune_temp[N], 150, heater_maxtemp[N] - 15, []{ _lcd_autotune(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, N, MSG_PID_AUTOTUNE_E, &autotune_temp[N], 150, heater_maxtemp[N] - HOTEND_OVERSHOOT, []{ _lcd_autotune(MenuItemBase::itemIndex); }); #else #define PID_EDIT_MENU_ITEMS(N) _PID_EDIT_MENU_ITEMS(N); #endif diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index e5ad0f9cbf..a95cecf086 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -331,7 +331,7 @@ void menu_advanced_settings(); BACK_ITEM(MSG_CONFIGURATION); EDIT_ITEM(percent, MSG_FAN_SPEED, &ui.preheat_fan_speed[material], 0, 255); #if HAS_TEMP_HOTEND - EDIT_ITEM(int3, MSG_NOZZLE, &ui.preheat_hotend_temp[material], MINTEMP_ALL, MAXTEMP_ALL - 15); + EDIT_ITEM(int3, MSG_NOZZLE, &ui.preheat_hotend_temp[material], MINTEMP_ALL, MAXTEMP_ALL - HOTEND_OVERSHOOT); #endif #if HAS_HEATED_BED EDIT_ITEM(int3, MSG_BED, &ui.preheat_bed_temp[material], BED_MINTEMP, BED_MAX_TARGET); diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 46aee8f7a9..84bc275ce9 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -83,7 +83,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { BACK_ITEM(MSG_BACK); ACTION_ITEM(MSG_PREHEAT_1, []{ _change_filament(ui.preheat_hotend_temp[0]); }); ACTION_ITEM(MSG_PREHEAT_2, []{ _change_filament(ui.preheat_hotend_temp[1]); }); - EDIT_ITEM_FAST(int3, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[_change_filament_extruder].target, EXTRUDE_MINTEMP, heater_maxtemp[extruder] - 15, []{ + EDIT_ITEM_FAST(int3, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[_change_filament_extruder].target, EXTRUDE_MINTEMP, heater_maxtemp[extruder] - HOTEND_OVERSHOOT, []{ _change_filament(thermalManager.temp_hotend[_change_filament_extruder].target); }); END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 1e610ec190..e11fa39d46 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -50,7 +50,7 @@ uint8_t MarlinUI::preheat_fan_speed[2]; void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb) { #if HAS_HOTEND if (indh >= 0 && ui.preheat_hotend_temp[indh] > 0) - setTargetHotend(_MIN(heater_maxtemp[e] - 15, ui.preheat_hotend_temp[indh]), e); + setTargetHotend(_MIN(heater_maxtemp[e] - HOTEND_OVERSHOOT, ui.preheat_hotend_temp[indh]), e); #else UNUSED(e); UNUSED(temph); @@ -163,14 +163,14 @@ void menu_temperature() { // Nozzle [1-5]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - 15, []{ thermalManager.start_watching_hotend(0); }); + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(0); }); #elif HAS_MULTI_HOTEND HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - 15, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif #if ENABLED(SINGLENOZZLE) - EDIT_ITEM_FAST(uint16_3, MSG_NOZZLE_STANDBY, &singlenozzle_temp[active_extruder ? 0 : 1], 0, HEATER_0_MAXTEMP - 15); + EDIT_ITEM_FAST(uint16_3, MSG_NOZZLE_STANDBY, &singlenozzle_temp[active_extruder ? 0 : 1], 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); #endif // diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 4ef7e48fa3..2970130616 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -118,14 +118,14 @@ void menu_tune() { // Nozzle [1-4]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - 15, []{ thermalManager.start_watching_hotend(0); }); + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(0); }); #elif HAS_MULTI_HOTEND HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - 15, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif #if ENABLED(SINGLENOZZLE) - EDIT_ITEM_FAST(uint16_3, MSG_NOZZLE_STANDBY, &singlenozzle_temp[active_extruder ? 0 : 1], 0, HEATER_0_MAXTEMP - 15); + EDIT_ITEM_FAST(uint16_3, MSG_NOZZLE_STANDBY, &singlenozzle_temp[active_extruder ? 0 : 1], 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); #endif // diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index dde17b0192..b3579d3538 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -128,7 +128,7 @@ void _lcd_ubl_build_custom_mesh() { void _lcd_ubl_custom_mesh() { START_MENU(); BACK_ITEM(MSG_UBL_BUILD_MESH_MENU); - EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 15)); + EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); #if HAS_HEATED_BED EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP, BED_MAX_TARGET); #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 44de7cc40c..761e26f90d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -400,7 +400,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); - if (target > GHV(BED_MAX_TARGET, temp_range[heater].maxtemp - 15)) { + if (target > GHV(BED_MAX_TARGET, temp_range[heater].maxtemp - HOTEND_OVERSHOOT)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); return; diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index b4cba62b10..f59d894254 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -588,7 +588,7 @@ class Temperature { start_preheat_time(ee); #endif TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); - temp_hotend[ee].target = _MIN(celsius, temp_range[ee].maxtemp - 15); + temp_hotend[ee].target = _MIN(celsius, temp_range[ee].maxtemp - HOTEND_OVERSHOOT); start_watching_hotend(ee); } From c4d57462dc96f7da5c9e46600a9c6c2da41f537e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 04:49:31 -0500 Subject: [PATCH 0288/1454] Apply HAS_MULTI_HOTEND --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/Conditionals_post.h | 6 +++--- Marlin/src/module/tool_change.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index c47899b34c..ab8b812f55 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -475,7 +475,7 @@ #ifndef HOTEND_OVERSHOOT #define HOTEND_OVERSHOOT 15 #endif - #if HOTENDS_ > 1 + #if HOTENDS > 1 #define HAS_MULTI_HOTEND 1 #define HAS_HOTEND_OFFSET 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index b4f68fcf7b..5635453b64 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1753,7 +1753,7 @@ #if HAS_HOTEND && PIN_EXISTS(E0_AUTO_FAN) #define HAS_AUTO_FAN_0 1 #endif -#if HOTENDS > 1 && PIN_EXISTS(E1_AUTO_FAN) +#if HAS_MULTI_HOTEND && PIN_EXISTS(E1_AUTO_FAN) #define HAS_AUTO_FAN_1 1 #endif #if HOTENDS > 2 && PIN_EXISTS(E2_AUTO_FAN) @@ -1997,7 +1997,7 @@ */ #define WRITE_HEATER_0P(v) WRITE(HEATER_0_PIN, (v) ^ HEATER_0_INVERTING) -#if HOTENDS > 1 || ENABLED(HEATERS_PARALLEL) +#if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define WRITE_HEATER_1(v) WRITE(HEATER_1_PIN, (v) ^ HEATER_1_INVERTING) #if HOTENDS > 2 #define WRITE_HEATER_2(v) WRITE(HEATER_2_PIN, (v) ^ HEATER_2_INVERTING) @@ -2017,7 +2017,7 @@ #endif // HOTENDS > 4 #endif // HOTENDS > 3 #endif // HOTENDS > 2 -#endif // HOTENDS > 1 +#endif // HAS_MULTI_HOTEND || HEATERS_PARALLEL #if ENABLED(HEATERS_PARALLEL) #define WRITE_HEATER_0(v) { WRITE_HEATER_0P(v); WRITE_HEATER_1(v); } #else diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index c1060c1233..9908d37cda 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1244,7 +1244,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // Migrate the temperature to the new hotend - #if HOTENDS > 1 + #if HAS_MULTI_HOTEND thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); #if HAS_DISPLAY thermalManager.set_heating_message(0); From 8f7f7f7c456198256aac208a3917d79db90cfff4 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 27 Apr 2020 03:13:47 -0700 Subject: [PATCH 0289/1454] Apply missed const& SPI optimization (#17734) Followup to eebb68cd7f --- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 2 +- Marlin/src/HAL/LPC1768/include/SPI.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index a8a7279ffb..a34037fde5 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -213,7 +213,7 @@ void SPIClass::begin() { spiBegin(); } -void SPIClass::beginTransaction(SPISettings cfg) { +void SPIClass::beginTransaction(const SPISettings &cfg) { uint8_t spiRate; switch (cfg.spiRate()) { case 8000000: spiRate = 0; break; diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index 3bc0299b14..4e84c0efa5 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -31,7 +31,7 @@ class SPISettings { public: SPISettings(uint32_t speed, int, int) : spi_speed(speed) {}; - uint32_t spiRate() { return spi_speed; } + uint32_t spiRate() const { return spi_speed; } private: uint32_t spi_speed; }; From c7f9eb7b213d1f727cf62557737a24ee80f460eb Mon Sep 17 00:00:00 2001 From: ellensp Date: Mon, 27 Apr 2020 22:16:47 +1200 Subject: [PATCH 0290/1454] Allow M42 M with other parameters (#17744) --- Marlin/src/gcode/control/M42.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 4b2b7fc0f7..0d703ca4bd 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -56,9 +56,8 @@ void GcodeSuite::M42() { #ifdef INPUT_PULLDOWN case 3: pinMode(pin, INPUT_PULLDOWN); break; #endif - default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); + default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); return; } - return; } if (!parser.seenval('S')) return; From 65daf3ba4085888661c8f3e78305b670951b0844 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Mon, 27 Apr 2020 06:22:06 -0400 Subject: [PATCH 0291/1454] Fix G12 for SINGLENOZZLE (#17540) Co-authored-by: Scott Lahteine --- Marlin/src/libs/nozzle.cpp | 40 +++++++++++++++++++++++++++++++------- 1 file changed, 33 insertions(+), 7 deletions(-) diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 926845ced2..f3434a642d 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -142,22 +142,48 @@ Nozzle nozzle; void Nozzle::clean(const uint8_t &pattern, const uint8_t &strokes, const float &radius, const uint8_t &objects, const uint8_t cleans) { xyz_pos_t start[HOTENDS] = NOZZLE_CLEAN_START_POINT, end[HOTENDS] = NOZZLE_CLEAN_END_POINT, middle[HOTENDS] = NOZZLE_CLEAN_CIRCLE_MIDDLE; + const uint8_t arrPos = ANY(SINGLENOZZLE, MIXING_EXTRUDER) ? 0 : active_extruder; + + #if HAS_SOFTWARE_ENDSTOPS + + #define LIMIT_AXIS(A) do{ \ + LIMIT( start[arrPos].A, soft_endstop.min.A, soft_endstop.max.A); \ + LIMIT(middle[arrPos].A, soft_endstop.min.A, soft_endstop.max.A); \ + LIMIT( end[arrPos].A, soft_endstop.min.A, soft_endstop.max.A); \ + }while(0) + + LIMIT_AXIS(x); + LIMIT_AXIS(y); + LIMIT_AXIS(z); + + const bool radiusOutOfRange = (middle[arrPos].x + radius > soft_endstop.max.x) + || (middle[arrPos].x - radius < soft_endstop.min.x) + || (middle[arrPos].y + radius > soft_endstop.max.y) + || (middle[arrPos].y - radius < soft_endstop.min.y); + + if (radiusOutOfRange && pattern == 2) { + SERIAL_ECHOLNPGM("Warning: Radius Out of Range"); + return; + } + + #endif + if (pattern == 2) { if (!(cleans & (_BV(X_AXIS) | _BV(Y_AXIS)))) { - SERIAL_ECHOLNPGM("Warning : Clean Circle requires XY"); + SERIAL_ECHOLNPGM("Warning: Clean Circle requires XY"); return; } } else { - if (!TEST(cleans, X_AXIS)) start[active_extruder].x = end[active_extruder].x = current_position.x; - if (!TEST(cleans, Y_AXIS)) start[active_extruder].y = end[active_extruder].y = current_position.y; + if (!TEST(cleans, X_AXIS)) start[arrPos].x = end[arrPos].x = current_position.x; + if (!TEST(cleans, Y_AXIS)) start[arrPos].y = end[arrPos].y = current_position.y; } - if (!TEST(cleans, Z_AXIS)) start[active_extruder].z = end[active_extruder].z = current_position.z; + if (!TEST(cleans, Z_AXIS)) start[arrPos].z = end[arrPos].z = current_position.z; switch (pattern) { - case 1: zigzag(start[active_extruder], end[active_extruder], strokes, objects); break; - case 2: circle(start[active_extruder], middle[active_extruder], strokes, radius); break; - default: stroke(start[active_extruder], end[active_extruder], strokes); + case 1: zigzag(start[arrPos], end[arrPos], strokes, objects); break; + case 2: circle(start[arrPos], middle[arrPos], strokes, radius); break; + default: stroke(start[arrPos], end[arrPos], strokes); } } From 5ae45bab1826fc9c743d62a52f55cea5fe124b6b Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Mon, 27 Apr 2020 12:59:52 +0200 Subject: [PATCH 0292/1454] Adjustable XY_FREQUENCY_LIMIT (#17583) --- Marlin/Configuration_adv.h | 14 +++-- Marlin/src/gcode/config/M200-M205.cpp | 5 ++ Marlin/src/lcd/language/language_en.h | 2 + Marlin/src/lcd/language/language_fr.h | 2 + Marlin/src/lcd/menu/menu_advanced.cpp | 12 +++-- Marlin/src/module/planner.cpp | 76 ++++++++++++--------------- Marlin/src/module/planner.h | 32 ++++++----- 7 files changed, 82 insertions(+), 61 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e01f71d7e2..7a125b06d7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -784,10 +784,16 @@ #define SLOWDOWN_DIVISOR 2 #endif -// Frequency limit -// See nophead's blog for more info -// Not working O -//#define XY_FREQUENCY_LIMIT 15 +/** + * XY Frequency limit + * Reduce resonance by limiting the frequency of small zigzag infill moves. + * See http://hydraraptor.blogspot.com/2010/12/frequency-limit.html + * Use M201 F G to change limits at runtime. + */ +//#define XY_FREQUENCY_LIMIT 10 // (Hz) Maximum frequency of small zigzag infill moves. Set with M201 F. +#ifdef XY_FREQUENCY_LIMIT + #define XY_FREQUENCY_MIN_PERCENT 5 // (percent) Minimum FR percentage to apply. Set with M201 G. +#endif // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 30e6f0f564..b717dc3365 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -60,6 +60,11 @@ void GcodeSuite::M201() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; + #ifdef XY_FREQUENCY_LIMIT + if (parser.seenval('F')) planner.set_frequency_limit(parser.value_byte()); + if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100; + #endif + LOOP_XYZE(i) { if (parser.seen(axis_codes[i])) { const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index e9cd043e6d..f9fb84cc80 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -301,6 +301,8 @@ namespace Language_en { PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Travel"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequency max"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("steps/mm"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 23258b9015..3daac87a28 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -262,6 +262,8 @@ namespace Language_fr { PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accélération"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acc.rétraction"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acc.course"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Fréquence max"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Vitesse min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pas/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pas/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pas/mm"); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 166442079d..0322ad1ff2 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -405,9 +405,9 @@ void menu_cancelobject(); #endif #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST(long5_25, MSG_AMAX_##Q, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.reset_acceleration_rates(); }) - EDIT_AMAX(A,100); - EDIT_AMAX(B,100); - EDIT_AMAX(C, 10); + EDIT_AMAX(A, 100); + EDIT_AMAX(B, 100); + EDIT_AMAX(C, 10); #if ENABLED(DISTINCT_E_FACTORS) EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); @@ -417,6 +417,12 @@ void menu_cancelobject(); EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); #endif + #ifdef XY_FREQUENCY_LIMIT + EDIT_ITEM(uint16_3, MSG_XY_FREQUENCY_LIMIT, &planner.xy_freq_limit_hz, 0, 100, refresh_frequency_limit(), true); + editable.uint8 = ROUND(planner.xy_freq_min_speed_factor * 255 * 100); // percent to u8 + EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); + #endif + END_MENU(); } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 0643ba1cb3..ad9dffe4ea 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -113,7 +113,7 @@ Planner planner; - // public: +// public: /** * A ring buffer of moves described in steps @@ -200,10 +200,9 @@ float Planner::previous_nominal_speed_sqr; #endif #ifdef XY_FREQUENCY_LIMIT - // Old direction bits. Used for speed calculations - unsigned char Planner::old_direction_bits = 0; - // Segment times (in µs). Used for speed calculations - xy_ulong_t Planner::axis_segment_time_us[3] = { { MAX_FREQ_TIME_US + 1, MAX_FREQ_TIME_US + 1 } }; + int8_t Planner::xy_freq_limit_hz = XY_FREQUENCY_LIMIT; + float Planner::xy_freq_min_speed_factor = (XY_FREQUENCY_MIN_PERCENT) * 0.01f; + int32_t Planner::xy_freq_min_interval_us = LROUND(1000000.0 / (XY_FREQUENCY_LIMIT)); #endif #if ENABLED(LIN_ADVANCE) @@ -2006,7 +2005,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill #if EITHER(SLOWDOWN, ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT) // Segment time im micro seconds - uint32_t segment_time_us = LROUND(1000000.0f / inverse_secs); + int32_t segment_time_us = LROUND(1000000.0f / inverse_secs); #endif #if ENABLED(SLOWDOWN) @@ -2014,9 +2013,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #define SLOWDOWN_DIVISOR 2 #endif if (WITHIN(moves_queued, 2, (BLOCK_BUFFER_SIZE) / (SLOWDOWN_DIVISOR) - 1)) { - if (segment_time_us < settings.min_segment_time_us) { - // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. - const uint32_t nst = segment_time_us + LROUND(2 * (settings.min_segment_time_us - segment_time_us) / moves_queued); + const int32_t time_diff = settings.min_segment_time_us - segment_time_us; + if (time_diff > 0) { + // Buffer is draining so add extra time. The amount of time added increases if the buffer is still emptied more. + const int32_t nst = segment_time_us + LROUND(2 * time_diff / moves_queued); inverse_secs = 1000000.0f / nst; #if defined(XY_FREQUENCY_LIMIT) || HAS_SPI_LCD segment_time_us = nst; @@ -2072,42 +2072,36 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } #endif - // Max segment time in µs. #ifdef XY_FREQUENCY_LIMIT - // Check and limit the xy direction change frequency - const unsigned char direction_change = block->direction_bits ^ old_direction_bits; - old_direction_bits = block->direction_bits; - segment_time_us = LROUND((float)segment_time_us / speed_factor); + static uint8_t old_direction_bits; // = 0 - uint32_t xs0 = axis_segment_time_us[0].x, - xs1 = axis_segment_time_us[1].x, - xs2 = axis_segment_time_us[2].x, - ys0 = axis_segment_time_us[0].y, - ys1 = axis_segment_time_us[1].y, - ys2 = axis_segment_time_us[2].y; + if (xy_freq_limit_hz) { + // Check and limit the xy direction change frequency + const uint8_t direction_change = block->direction_bits ^ old_direction_bits; + old_direction_bits = block->direction_bits; + segment_time_us = LROUND(float(segment_time_us) / speed_factor); - if (TEST(direction_change, X_AXIS)) { - xs2 = axis_segment_time_us[2].x = xs1; - xs1 = axis_segment_time_us[1].x = xs0; - xs0 = 0; + static int32_t xs0, xs1, xs2, ys0, ys1, ys2; + if (segment_time_us > xy_freq_min_interval_us) + xs2 = xs1 = ys2 = ys1 = xy_freq_min_interval_us; + else { + xs2 = xs1; xs1 = xs0; + ys2 = ys1; ys1 = ys0; + } + xs0 = TEST(direction_change, X_AXIS) ? segment_time_us : xy_freq_min_interval_us; + ys0 = TEST(direction_change, Y_AXIS) ? segment_time_us : xy_freq_min_interval_us; + + if (segment_time_us < xy_freq_min_interval_us) { + const int32_t least_xy_segment_time = _MIN(_MAX(xs0, xs1, xs2), _MAX(ys0, ys1, ys2)); + if (least_xy_segment_time < xy_freq_min_interval_us) { + float freq_xy_feedrate = (speed_factor * least_xy_segment_time) / xy_freq_min_interval_us; + NOLESS(freq_xy_feedrate, xy_freq_min_speed_factor); + NOMORE(speed_factor, freq_xy_feedrate); + } + } } - xs0 = axis_segment_time_us[0].x = xs0 + segment_time_us; - if (TEST(direction_change, Y_AXIS)) { - ys2 = axis_segment_time_us[2].y = axis_segment_time_us[1].y; - ys1 = axis_segment_time_us[1].y = axis_segment_time_us[0].y; - ys0 = 0; - } - ys0 = axis_segment_time_us[0].y = ys0 + segment_time_us; - - const uint32_t max_x_segment_time = _MAX(xs0, xs1, xs2), - max_y_segment_time = _MAX(ys0, ys1, ys2), - min_xy_segment_time = _MIN(max_x_segment_time, max_y_segment_time); - if (min_xy_segment_time < MAX_FREQ_TIME_US) { - const float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME_US); - NOMORE(speed_factor, low_sf); - } #endif // XY_FREQUENCY_LIMIT // Correct the speed @@ -2832,7 +2826,7 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { const bool was_enabled = stepper.suspend(); #endif - millis_t bbru = block_buffer_runtime_us; + uint32_t bbru = block_buffer_runtime_us; #ifdef __AVR__ // Reenable Stepper ISR @@ -2844,7 +2838,7 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { // Doesn't matter because block_buffer_runtime_us is already too small an estimation. bbru >>= 10; // limit to about a minute. - NOMORE(bbru, 0xFFFFul); + NOMORE(bbru, 0x0000FFFFUL); return bbru; } diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index bf585320de..e9658f2c60 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -352,6 +352,23 @@ class Planner { #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) static bool abort_on_endstop_hit; #endif + #ifdef XY_FREQUENCY_LIMIT + static int8_t xy_freq_limit_hz; // Minimum XY frequency setting + static float xy_freq_min_speed_factor; // Minimum speed factor setting + static int32_t xy_freq_min_interval_us; // Minimum segment time based on xy_freq_limit_hz + static inline void refresh_frequency_limit() { + //xy_freq_min_interval_us = xy_freq_limit_hz ?: LROUND(1000000.0f / xy_freq_limit_hz); + if (xy_freq_limit_hz) + xy_freq_min_interval_us = LROUND(1000000.0f / xy_freq_limit_hz); + } + static inline void set_min_speed_factor_u8(const uint8_t v255) { + xy_freq_min_speed_factor = float(ui8_to_percent(v255)) / 100; + } + static inline void set_frequency_limit(const uint8_t hz) { + xy_freq_limit_hz = constrain(hz, 0, 100); + refresh_frequency_limit(); + } + #endif private: @@ -375,23 +392,12 @@ class Planner { #endif #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - /** - * Counters to manage disabling inactive extruders - */ + // Counters to manage disabling inactive extruders static uint8_t g_uc_extruder_last_move[EXTRUDERS]; - #endif // DISABLE_INACTIVE_EXTRUDER - - #ifdef XY_FREQUENCY_LIMIT - // Used for the frequency limit - #define MAX_FREQ_TIME_US (uint32_t)(1000000.0 / XY_FREQUENCY_LIMIT) - // Old direction bits. Used for speed calculations - static unsigned char old_direction_bits; - // Segment times (in µs). Used for speed calculations - static xy_ulong_t axis_segment_time_us[3]; #endif #if HAS_SPI_LCD - volatile static uint32_t block_buffer_runtime_us; //Theoretical block buffer runtime in µs + volatile static uint32_t block_buffer_runtime_us; // Theoretical block buffer runtime in µs #endif public: From fec416f9dbcb365cfd14116eacb728296bb23874 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 06:27:54 -0500 Subject: [PATCH 0293/1454] LCD preheat followup --- Marlin/src/lcd/menu/menu_temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index e11fa39d46..6aa6b32659 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -65,7 +65,7 @@ void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t i #if FAN_COUNT > 1 active_extruder < FAN_COUNT ? active_extruder : #endif - 0), ui.preheat_fan_speed[m] + 0), ui.preheat_fan_speed[indh] ); #endif ui.return_to_status(); From fc983836594dd1486c13d5a5c7bd01ab712a35d2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 05:31:37 -0500 Subject: [PATCH 0294/1454] Update home bump assert --- Marlin/src/inc/SanityCheck.h | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 8e37362971..03701c7cc3 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1417,9 +1417,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Homing */ -#if X_HOME_BUMP_MM < 0 || Y_HOME_BUMP_MM < 0 || Z_HOME_BUMP_MM < 0 - #error "[XYZ]_HOME_BUMP_MM must be greater than or equal to 0." -#endif +constexpr float hbm[] = HOMING_BUMP_MM; +static_assert(COUNT(hbm) == XYZ, "HOMING_BUMP_MM requires X, Y, and Z elements."); +static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."); +static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."); +static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."); #if ENABLED(CODEPENDENT_XY_HOMING) #if ENABLED(QUICK_HOME) From 967c1d853489619e09381dddfecdac44a8fc1805 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 18:39:47 -0500 Subject: [PATCH 0295/1454] Do SD sort order in CardReader --- Marlin/src/lcd/extui/ui_api.cpp | 8 +------- Marlin/src/lcd/menu/menu_media.cpp | 9 +-------- Marlin/src/sd/cardreader.cpp | 2 +- Marlin/src/sd/cardreader.h | 2 ++ 4 files changed, 5 insertions(+), 16 deletions(-) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 4d6815d638..9301a2ae3b 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1039,13 +1039,7 @@ namespace ExtUI { bool FileList::seek(const uint16_t pos, const bool skip_range_check) { #if ENABLED(SDSUPPORT) if (!skip_range_check && (pos + 1) > count()) return false; - const uint16_t nr = - #if ENABLED(SDCARD_RATHERRECENTFIRST) && DISABLED(SDCARD_SORT_ALPHA) - count() - 1 - - #endif - pos; - - card.getfilename_sorted(nr); + card.getfilename_sorted(SD_ORDER(pos, count())); return card.filename[0] != '\0'; #else UNUSED(pos); diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 777ce1beff..3c7c9dff8e 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -140,14 +140,7 @@ void menu_media() { if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { if (_menuLineNr == _thisItemNr) { - const uint16_t nr = - #if ENABLED(SDCARD_RATHERRECENTFIRST) && DISABLED(SDCARD_SORT_ALPHA) - fileCnt - 1 - - #endif - i; - - card.getfilename_sorted(nr); - + card.getfilename_sorted(SD_ORDER(i, fileCnt)); if (card.flag.filenameIsDir) MENU_ITEM(sdfolder, MSG_MEDIA_MENU, card); else diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index bf80657a2f..54a17f57aa 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -924,7 +924,7 @@ void CardReader::cdroot() { // Init sort order. for (uint16_t i = 0; i < fileCnt; i++) { - sort_order[i] = TERN(SDCARD_RATHERRECENTFIRST, fileCnt - 1 - i, i); + sort_order[i] = SD_ORDER(i, fileCnt); // If using RAM then read all filenames now. #if ENABLED(SDSORT_USES_RAM) selectFileByIndex(i); diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index ef1912c8bd..b5723694a9 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -29,6 +29,8 @@ #define SD_RESORT 1 #endif +#define SD_ORDER(N,C) (TERN(SDCARD_RATHERRECENTFIRST, C - 1 - (N), N)) + #define MAX_DIR_DEPTH 10 // Maximum folder depth #define MAXDIRNAMELENGTH 8 // DOS folder name size #define MAXPATHNAMELENGTH (1 + (MAXDIRNAMELENGTH + 1) * (MAX_DIR_DEPTH) + 1 + FILENAME_LENGTH) // "/" + N * ("ADIRNAME/") + "filename.ext" From c536b8de629807b489f054051bb120457f112a11 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 17:53:06 -0500 Subject: [PATCH 0296/1454] Apply ternary macros --- Marlin/src/feature/runout.h | 46 ++++--------- Marlin/src/gcode/feature/pause/M600.cpp | 8 +-- Marlin/src/lcd/menu/menu.cpp | 77 ++++++---------------- Marlin/src/lcd/menu/menu_advanced.cpp | 8 +-- Marlin/src/lcd/menu/menu_configuration.cpp | 14 +--- Marlin/src/lcd/menu/menu_game.cpp | 8 +-- Marlin/src/lcd/menu/menu_info.cpp | 61 +++++------------ Marlin/src/lcd/menu/menu_mixer.cpp | 6 +- Marlin/src/lcd/menu/menu_mmu2.cpp | 3 +- Marlin/src/lcd/menu/menu_motion.cpp | 44 ++++--------- Marlin/src/lcd/ultralcd.cpp | 2 +- Marlin/src/lcd/ultralcd.h | 28 +++----- Marlin/src/module/planner.h | 4 +- 13 files changed, 79 insertions(+), 230 deletions(-) diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index b975551c6e..056fc4f5cd 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -100,11 +100,9 @@ class TFilamentMonitor : public FilamentMonitorBase { // Give the response a chance to update its counter. static inline void run() { - if (enabled && !filament_ran_out && (printingIsActive() - #if ENABLED(ADVANCED_PAUSE_FEATURE) - || did_pause_print - #endif - )) { + if ( enabled && !filament_ran_out + && (printingIsActive() || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) + ) { #ifdef FILAMENT_RUNOUT_DISTANCE_MM cli(); // Prevent RunoutResponseDelayed::block_completed from accumulating here #endif @@ -153,11 +151,7 @@ class FilamentSensorBase { // Return a bitmask of runout flag states (1 bits always indicates runout) static inline uint8_t poll_runout_states() { - return (poll_runout_pins() - #if DISABLED(FIL_RUNOUT_INVERTING) - ^ uint8_t(_BV(NUM_RUNOUT_SENSORS) - 1) - #endif - ); + return poll_runout_pins() ^ uint8_t(TERN0(FIL_RUNOUT_INVERTING, _BV(NUM_RUNOUT_SENSORS) - 1)); } #undef INIT_RUNOUT_PIN @@ -217,26 +211,14 @@ class FilamentSensorBase { private: static inline bool poll_runout_state(const uint8_t extruder) { const uint8_t runout_states = poll_runout_states(); - #if NUM_RUNOUT_SENSORS == 1 UNUSED(extruder); + #else + if ( !TERN0(DUAL_X_CARRIAGE, dxc_is_duplicating()) + && !TERN0(MULTI_NOZZLE_DUPLICATION, extruder_duplication_enabled) + ) return TEST(runout_states, extruder); // A specific extruder ran out #endif - - if (true - #if NUM_RUNOUT_SENSORS > 1 - #if ENABLED(DUAL_X_CARRIAGE) - && (dual_x_carriage_mode == DXC_DUPLICATION_MODE || dual_x_carriage_mode == DXC_MIRRORED_MODE) - #elif ENABLED(MULTI_NOZZLE_DUPLICATION) - && extruder_duplication_enabled - #else - && false - #endif - #endif - ) return runout_states; // Any extruder - - #if NUM_RUNOUT_SENSORS > 1 - return TEST(runout_states, extruder); // Specific extruder - #endif + return !!runout_states; // Any extruder ran out } public: @@ -302,9 +284,7 @@ class FilamentSensorBase { static inline void block_completed(const block_t* const b) { if (b->steps.x || b->steps.y || b->steps.z - #if ENABLED(ADVANCED_PAUSE_FEATURE) - || did_pause_print // Allow pause purge move to re-trigger runout state - #endif + || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print) // Allow pause purge move to re-trigger runout state ) { // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. const uint8_t e = b->extruder; @@ -338,11 +318,7 @@ class FilamentSensorBase { typedef TFilamentMonitor< #ifdef FILAMENT_RUNOUT_DISTANCE_MM RunoutResponseDelayed, - #if ENABLED(FILAMENT_MOTION_SENSOR) - FilamentSensorEncoder - #else - FilamentSensorSwitch - #endif + TERN(FILAMENT_MOTION_SENSOR, FilamentSensorEncoder, FilamentSensorSwitch) #else RunoutResponseDebounced, FilamentSensorSwitch #endif diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 5193864a07..c22e32ceee 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -103,12 +103,8 @@ void GcodeSuite::M600() { #if EXTRUDERS > 1 // Change toolhead if specified const uint8_t active_extruder_before_filament_change = active_extruder; - if ( - active_extruder != target_extruder - #if ENABLED(DUAL_X_CARRIAGE) - && dual_x_carriage_mode != DXC_DUPLICATION_MODE && dual_x_carriage_mode != DXC_MIRRORED_MODE - #endif - ) tool_change(target_extruder, false); + if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !dxc_is_duplicating())) + tool_change(target_extruder, false); #endif // Initial retract before move to filament change position diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 1518e1f50a..39e8899313 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -87,11 +87,7 @@ void MarlinUI::save_previous_screen() { screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items }; } -void MarlinUI::_goto_previous_screen( - #if ENABLED(TURBO_BACK_MENU_ITEM) - const bool is_back/*=false*/ - #endif -) { +void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back/*=false*/)) { #if DISABLED(TURBO_BACK_MENU_ITEM) constexpr bool is_back = false; #endif @@ -233,33 +229,15 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co doubleclick_expire_ms = millis() + DOUBLECLICK_MAX_INTERVAL; } else if (screen == status_screen && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { - - #if ENABLED(BABYSTEP_WITHOUT_HOMING) - constexpr bool can_babystep = true; - #else - const bool can_babystep = all_axes_known(); - #endif - #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE) - constexpr bool should_babystep = true; - #else - const bool should_babystep = printer_busy(); - #endif - - if (should_babystep && can_babystep) { - screen = - #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - lcd_babystep_zoffset - #else - lcd_babystep_z - #endif - ; - } - #if ENABLED(MOVE_Z_WHEN_IDLE) - else { + if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) + && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) + screen = TERN(BABYSTEP_ZPROBE_OFFSET, lcd_babystep_zoffset, lcd_babystep_z); + else { + #if ENABLED(MOVE_Z_WHEN_IDLE) move_menu_scale = MOVE_Z_IDLE_MULTIPLICATOR; screen = lcd_move_z; - } - #endif + #endif + } } #endif @@ -277,11 +255,8 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co // Re-initialize custom characters that may be re-used #if HAS_CHARACTER_LCD - if (true - #if ENABLED(AUTO_BED_LEVELING_UBL) - && !ubl.lcd_map_control - #endif - ) set_custom_characters(screen == status_screen ? CHARSET_INFO : CHARSET_MENU); + if (TERN1(AUTO_BED_LEVELING_UBL, !ubl.lcd_map_control)) + set_custom_characters(screen == status_screen ? CHARSET_INFO : CHARSET_MENU); #endif refresh(LCDVIEW_CALL_REDRAW_NEXT); @@ -377,13 +352,10 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { const float diff = planner.steps_to_mm[Z_AXIS] * babystep_increment, new_probe_offset = probe.offset.z + diff, - new_offs = - #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - do_probe ? new_probe_offset : hotend_offset[active_extruder].z - diff - #else - new_probe_offset - #endif - ; + new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET + , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - diff + , new_probe_offset + ); if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) { babystep.add_steps(Z_AXIS, babystep_increment); @@ -397,30 +369,23 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { } } if (ui.should_draw()) { - #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - if (!do_probe) - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_HOTEND_OFFSET_Z), ftostr54sign(hotend_offset[active_extruder].z)); - #endif if (do_probe) { MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), BABYSTEP_TO_STR(probe.offset.z)); TERN_(BABYSTEP_ZPROBE_GFX_OVERLAY, _lcd_zoffset_overlay_gfx(probe.offset.z)); } + else { + #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) + MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_HOTEND_OFFSET_Z), ftostr54sign(hotend_offset[active_extruder].z)); + #endif + } } } #endif // BABYSTEP_ZPROBE_OFFSET #if ENABLED(EEPROM_SETTINGS) - void lcd_store_settings() { - const bool saved = settings.save(); - ui.completion_feedback(saved); - UNUSED(saved); - } - void lcd_load_settings() { - const bool loaded = settings.load(); - ui.completion_feedback(loaded); - UNUSED(loaded); - } + void lcd_store_settings() { ui.completion_feedback(settings.save()); } + void lcd_load_settings() { ui.completion_feedback(settings.load()); } #endif void _lcd_draw_homing() { diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 0322ad1ff2..0109138a57 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -132,13 +132,7 @@ void menu_cancelobject(); #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) - constexpr float extrude_maxlength = - #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - EXTRUDE_MAXLENGTH - #else - 999 - #endif - ; + constexpr float extrude_maxlength = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 999); EDIT_ITEM_FAST(float3, MSG_FILAMENT_UNLOAD, &fc_settings[active_extruder].unload_length, 0, extrude_maxlength); #if EXTRUDERS > 1 diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index a95cecf086..0c58b24681 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -206,13 +206,7 @@ void menu_advanced_settings(); #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) void bltouch_report() { SERIAL_ECHOLNPAIR("EEPROM Last BLTouch Mode - ", (int)bltouch.last_written_mode); - SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " - #if ENABLED(BLTOUCH_SET_5V_MODE) - "5V" - #else - "OD" - #endif - ); + SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD")); char mess[21]; strcpy_P(mess, PSTR("BLTouch Mode - ")); strcpy_P(&mess[15], bltouch.last_written_mode ? PSTR("5V") : PSTR("OD")); @@ -411,11 +405,7 @@ void menu_configuration() { // #if ENABLED(CASE_LIGHT_MENU) #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) - if (true - #if DISABLED(CASE_LIGHT_USE_NEOPIXEL) - && PWM_PIN(CASE_LIGHT_PIN) - #endif - ) + if (TERN1(CASE_LIGHT_USE_NEOPIXEL, PWM_PIN(CASE_LIGHT_PIN))) SUBMENU(MSG_CASE_LIGHT, menu_case_light); else #endif diff --git a/Marlin/src/lcd/menu/menu_game.cpp b/Marlin/src/lcd/menu/menu_game.cpp index c2ac9f62a9..edf36e521b 100644 --- a/Marlin/src/lcd/menu/menu_game.cpp +++ b/Marlin/src/lcd/menu/menu_game.cpp @@ -29,13 +29,7 @@ void menu_game() { START_MENU(); - BACK_ITEM( - #if ENABLED(LCD_INFO_MENU) - MSG_INFO_MENU - #else - MSG_MAIN - #endif - ); + BACK_ITEM(TERN(LCD_INFO_MENU, MSG_INFO_MENU, MSG_MAIN)); #if ENABLED(MARLIN_BRICKOUT) SUBMENU(MSG_BRICKOUT, brickout.enter_game); #endif diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index f7b895679a..1b52c182ba 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -51,19 +51,24 @@ printStatistics stats = print_job_timer.getStats(); - START_SCREEN(); // 12345678901234567890 - VALUE_ITEM(MSG_INFO_PRINT_COUNT, i16tostr3left(stats.totalPrints), SS_LEFT); // Print Count: 999 - VALUE_ITEM(MSG_INFO_COMPLETED_PRINTS, i16tostr3left(stats.finishedPrints), SS_LEFT); // Completed : 666 + char buffer[21]; - STATIC_ITEM(MSG_INFO_PRINT_TIME, SS_LEFT); // Total print Time: + START_SCREEN(); // 12345678901234567890 + VALUE_ITEM(MSG_INFO_PRINT_COUNT, i16tostr3left(stats.totalPrints), SS_LEFT); // Print Count: 999 + VALUE_ITEM(MSG_INFO_COMPLETED_PRINTS, i16tostr3left(stats.finishedPrints), SS_LEFT); // Completed : 666 + + STATIC_ITEM(MSG_INFO_PRINT_TIME, SS_LEFT); // Total print Time: STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.printTime).toString(buffer)); // > 99y 364d 23h 59m 59s - STATIC_ITEM(MSG_INFO_PRINT_LONGEST, SS_LEFT); // Longest job time: + STATIC_ITEM(MSG_INFO_PRINT_LONGEST, SS_LEFT); // Longest job time: STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.longestPrint).toString(buffer)); // > 99y 364d 23h 59m 59s - STATIC_ITEM(MSG_INFO_PRINT_FILAMENT, SS_LEFT); // Extruded total: - sprintf_P(buffer, PSTR("%ld.%im"), long(stats.filamentUsed / 1000), int16_t(stats.filamentUsed / 100) % 10); - STATIC_ITEM_P(PSTR("> "), SS_LEFT, buffer); // > 125m + STATIC_ITEM(MSG_INFO_PRINT_FILAMENT, SS_LEFT); // Extruded total: + sprintf_P(buffer, PSTR("%ld.%im") + , long(stats.filamentUsed / 1000) + , int16_t(stats.filamentUsed / 100) % 10 + ); + STATIC_ITEM_P(PSTR("> "), SS_LEFT, buffer); // > 125m #if SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0 strcpy_P(buffer, GET_TEXT(MSG_SERVICE_IN)); @@ -171,16 +176,7 @@ void menu_info_thermistors() { #endif #if EXTRUDERS - { - STATIC_ITEM( - #if WATCH_HOTENDS - MSG_INFO_RUNAWAY_ON - #else - MSG_INFO_RUNAWAY_OFF - #endif - , SS_LEFT - ); - } + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if HAS_HEATED_BED @@ -191,34 +187,17 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR("BED:" THERMISTOR_NAME), SS_INVERT); VALUE_ITEM_P(MSG_INFO_MIN_TEMP, STRINGIFY(BED_MINTEMP), SS_LEFT); VALUE_ITEM_P(MSG_INFO_MAX_TEMP, STRINGIFY(BED_MAXTEMP), SS_LEFT); - STATIC_ITEM( - #if WATCH_BED - MSG_INFO_RUNAWAY_ON - #else - MSG_INFO_RUNAWAY_OFF - #endif - , SS_LEFT - ); - } + STATIC_ITEM(TERN(WATCH_BED, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if HAS_HEATED_CHAMBER - { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_CHAMBER #include "../thermistornames.h" STATIC_ITEM_P(PSTR("CHAM:" THERMISTOR_NAME), SS_INVERT); VALUE_ITEM_P(MSG_INFO_MIN_TEMP, STRINGIFY(CHAMBER_MINTEMP), SS_LEFT); VALUE_ITEM_P(MSG_INFO_MAX_TEMP, STRINGIFY(CHAMBER_MAXTEMP), SS_LEFT); - STATIC_ITEM( - #if WATCH_CHAMBER - MSG_INFO_RUNAWAY_ON - #else - MSG_INFO_RUNAWAY_OFF - #endif - , SS_LEFT - ); - } + STATIC_ITEM(TERN(WATCH_CHAMBER, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif END_SCREEN(); @@ -295,13 +274,7 @@ void menu_info() { START_MENU(); BACK_ITEM(MSG_MAIN); #if ENABLED(LCD_PRINTER_INFO_IS_BOOTSCREEN) - SUBMENU(MSG_INFO_PRINTER_MENU, ( - #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) - menu_show_custom_bootscreen - #else - menu_show_marlin_bootscreen - #endif - )); + SUBMENU(MSG_INFO_PRINTER_MENU, TERN(SHOW_CUSTOM_BOOTSCREEN, menu_show_custom_bootscreen, menu_show_marlin_bootscreen)); #else SUBMENU(MSG_INFO_PRINTER_MENU, menu_info_printer); // Printer Info > SUBMENU(MSG_INFO_BOARD_MENU, menu_info_board); // Board Info > diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index eeb01b62fa..e830b49a99 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -237,11 +237,7 @@ void menu_mixer() { BACK_ITEM(MSG_MAIN); v_index = mixer.get_current_vtool(); - EDIT_ITEM(uint8, MSG_ACTIVE_VTOOL, &v_index, 0, MIXING_VIRTUAL_TOOLS - 1, _lcd_mixer_select_vtool - #if HAS_DUAL_MIXING - , true - #endif - ); + EDIT_ITEM(uint8, MSG_ACTIVE_VTOOL, &v_index, 0, MIXING_VIRTUAL_TOOLS - 1, _lcd_mixer_select_vtool, ENABLED(HAS_DUAL_MIXING)); #if HAS_DUAL_MIXING { diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index 779f94d14f..e2ce919340 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -54,8 +54,7 @@ void _mmu2_load_filament(uint8_t index) { ui.reset_status(); } void action_mmu2_load_all() { - LOOP_L_N(i, EXTRUDERS) - _mmu2_load_filament(i); + LOOP_L_N(i, EXTRUDERS) _mmu2_load_filament(i); ui.return_to_status(); } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 0e5a29c9c7..9e069c92af 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -59,11 +59,11 @@ extern int8_t manual_move_axis; // Tell ui.update() to start a move to current_position" after a short delay. // inline void manual_move_to_current(AxisEnum axis - #if E_MANUAL > 1 + #if MULTI_MANUAL , const int8_t eindex=-1 #endif ) { - #if E_MANUAL > 1 + #if MULTI_MANUAL if (axis == E_AXIS) ui.manual_move_e_index = eindex >= 0 ? eindex : active_extruder; #endif manual_move_start_time = millis() + (move_menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves @@ -144,22 +144,14 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } #if E_MANUAL - static void lcd_move_e( - #if E_MANUAL > 1 - const int8_t eindex=-1 - #endif - ) { + static void lcd_move_e(TERN_(MULTI_MANUAL, const int8_t eindex=-1)) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { if (!ui.processing_manual_move) { const float diff = float(int32_t(ui.encoderPosition)) * move_menu_scale; - #if IS_KINEMATIC - manual_move_offset += diff; - #else - current_position.e += diff; - #endif + TERN(IS_KINEMATIC, manual_move_offset, current_position.e) += diff; manual_move_to_current(E_AXIS - #if E_MANUAL > 1 + #if MULTI_MANUAL , eindex #endif ); @@ -168,24 +160,14 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } ui.encoderPosition = 0; } if (ui.should_draw()) { - #if E_MANUAL > 1 + #if MULTI_MANUAL MenuItemBase::init(eindex); #endif MenuEditItemBase::draw_edit_screen( - GET_TEXT( - #if E_MANUAL > 1 - MSG_MOVE_EN - #else - MSG_MOVE_E - #endif - ), + GET_TEXT(TERN(MULTI_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), ftostr41sign(current_position.e - #if IS_KINEMATIC - + manual_move_offset - #endif - #if ENABLED(MANUAL_E_MOVES_RELATIVE) - - manual_move_e_origin - #endif + + TERN0(IS_KINEMATIC, manual_move_offset) + - TERN0(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin) ) ); } // should_draw @@ -261,11 +243,7 @@ void menu_move() { EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstops_enabled); #endif - if (true - #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) - && all_axes_homed() - #endif - ) { + if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) { if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) { SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); }); SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); @@ -332,7 +310,7 @@ void menu_move() { SUBMENU_MOVE_E(2); #endif - #elif E_MANUAL > 1 + #elif MULTI_MANUAL // Independent extruders with one E-stepper per hotend LOOP_L_N(n, E_MANUAL) SUBMENU_MOVE_E(n); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 82b93092d7..73f9cbaa29 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -638,7 +638,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { float manual_move_offset = 0; #endif - #if E_MANUAL > 1 + #if MULTI_MANUAL int8_t MarlinUI::manual_move_e_index = 0; #endif diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index f6d2e86cfd..33d7de2748 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -45,6 +45,10 @@ #define HAS_SLOW_BUTTONS 1 #endif +#if E_MANUAL > 1 + #define MULTI_MANUAL 1 +#endif + #if HAS_SPI_LCD #include "../MarlinCore.h" @@ -491,15 +495,9 @@ public: static void save_previous_screen(); // goto_previous_screen and go_back may also be used as menu item callbacks - #if ENABLED(TURBO_BACK_MENU_ITEM) - static void _goto_previous_screen(const bool is_back); - static inline void goto_previous_screen() { _goto_previous_screen(false); } - static inline void go_back() { _goto_previous_screen(true); } - #else - static void _goto_previous_screen(); - FORCE_INLINE static void goto_previous_screen() { _goto_previous_screen(); } - FORCE_INLINE static void go_back() { _goto_previous_screen(); } - #endif + static void _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back)); + static inline void goto_previous_screen() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, false)); } + static inline void go_back() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, true)); } static void return_to_status(); static inline bool on_status_screen() { return currentScreen == status_screen; } @@ -510,11 +508,7 @@ public: #endif FORCE_INLINE static void defer_status_screen(const bool defer=true) { - #if LCD_TIMEOUT_TO_STATUS - defer_return_to_status = defer; - #else - UNUSED(defer); - #endif + TERN(LCD_TIMEOUT_TO_STATUS, defer_return_to_status = defer, UNUSED(defer)); } static inline void goto_previous_screen_no_defer() { @@ -582,11 +576,7 @@ public: static uint32_t encoderPosition; - #if ENABLED(REVERSE_ENCODER_DIRECTION) - #define ENCODERBASE -1 - #else - #define ENCODERBASE +1 - #endif + #define ENCODERBASE (TERN(REVERSE_ENCODER_DIRECTION, -1, +1)) #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) static int8_t encoderDirection; diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index e9658f2c60..ebfb8dcb9e 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -137,9 +137,7 @@ typedef struct block_t { static constexpr uint8_t extruder = 0; #endif - #if ENABLED(MIXING_EXTRUDER) - MIXER_BLOCK_FIELD; // Normalized color for the mixing steppers - #endif + TERN_(MIXING_EXTRUDER, MIXER_BLOCK_FIELD); // Normalized color for the mixing steppers // Settings for the trapezoid generator uint32_t accelerate_until, // The index of the step event on which to stop acceleration From 5507b6073c0215894e9d00f787a64a9b57b16525 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 06:34:53 -0500 Subject: [PATCH 0297/1454] Fix dummy thermistors Fixes #17422 Co-Authored-By: Moeschus --- Marlin/src/module/temperature.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 761e26f90d..a0dec77793 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2277,9 +2277,9 @@ void Temperature::readings_ready() { #if HAS_HEATED_BED #if TEMPDIR(BED) < 0 - #define BEDCMP(A,B) ((A)<=(B)) + #define BEDCMP(A,B) ((A)<(B)) #else - #define BEDCMP(A,B) ((A)>=(B)) + #define BEDCMP(A,B) ((A)>(B)) #endif const bool bed_on = temp_bed.target > 0 || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount) > 0 @@ -2290,9 +2290,9 @@ void Temperature::readings_ready() { #if HAS_HEATED_CHAMBER #if TEMPDIR(CHAMBER) < 0 - #define CHAMBERCMP(A,B) ((A)<=(B)) + #define CHAMBERCMP(A,B) ((A)<(B)) #else - #define CHAMBERCMP(A,B) ((A)>=(B)) + #define CHAMBERCMP(A,B) ((A)>(B)) #endif const bool chamber_on = (temp_chamber.target > 0); if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); From 5d1498f2cb8a4bb4e709173184a96e46caeb306d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 06:57:05 -0500 Subject: [PATCH 0298/1454] Fix SKR Pro / GTR i2c pins Fixes #17297 Co-Authored-By: NAPCAL --- .../PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h index 0eab1abe53..1ba0a18d6a 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h @@ -245,8 +245,13 @@ extern "C" { #define PIN_SPI_SS PB12 // I2C Definitions -#define PIN_WIRE_SDA PB7 -#define PIN_WIRE_SCL PB6 +#if STM32F4X_PIN_NUM >= 176 + #define PIN_WIRE_SDA PH5 + #define PIN_WIRE_SCL PH4 +#else + #define PIN_WIRE_SDA PB7 + #define PIN_WIRE_SCL PB6 +#endif // Timer Definitions //Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c From 0777e391beb84f2f316141b5a24c8f4de5503c24 Mon Sep 17 00:00:00 2001 From: Martin Date: Mon, 27 Apr 2020 14:31:48 +0200 Subject: [PATCH 0299/1454] Add M115 Cap:BABYSTEPPING (#17691) --- Marlin/src/gcode/host/M115.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 144d42ff86..bd3a5b192b 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -108,6 +108,9 @@ void GcodeSuite::M115() { // MOTION_MODES (M80-M89) cap_line(PSTR("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES)); + // BABYSTEPPING (M290) + cap_line(PSTR("BABYSTEPPING"), ENABLED(BABYSTEPPING)); + // CHAMBER_TEMPERATURE (M141, M191) cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER)); From 37176ed2b9c3af5fbb2436d72a090b6d880f921e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 07:53:58 -0500 Subject: [PATCH 0300/1454] Apply maxtemp patch --- Marlin/src/lcd/extui/ui_api.cpp | 4 ++-- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_filament.cpp | 2 +- Marlin/src/lcd/menu/menu_temperature.cpp | 7 +++---- Marlin/src/lcd/menu/menu_tune.cpp | 2 +- Marlin/src/module/temperature.cpp | 1 + Marlin/src/module/temperature.h | 2 +- 7 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 9301a2ae3b..ab5aa887e7 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -946,7 +946,7 @@ namespace ExtUI { { #if HAS_HOTEND const int16_t e = heater - H0; - thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); + thermalManager.setTargetHotend(LROUND(constrain(value, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); #endif } } @@ -958,7 +958,7 @@ namespace ExtUI { #if HAS_HOTEND const int16_t e = extruder - E0; enableHeater(extruder); - thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); + thermalManager.setTargetHotend(LROUND(constrain(value, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT)), e); #endif } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 0109138a57..e510a8f339 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -298,7 +298,7 @@ void menu_cancelobject(); #if ENABLED(PID_AUTOTUNE_MENU) #define PID_EDIT_MENU_ITEMS(N) \ _PID_EDIT_MENU_ITEMS(N); \ - EDIT_ITEM_FAST_N(int3, N, MSG_PID_AUTOTUNE_E, &autotune_temp[N], 150, heater_maxtemp[N] - HOTEND_OVERSHOOT, []{ _lcd_autotune(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, N, MSG_PID_AUTOTUNE_E, &autotune_temp[N], 150, thermalManager.heater_maxtemp[N] - HOTEND_OVERSHOOT, []{ _lcd_autotune(MenuItemBase::itemIndex); }); #else #define PID_EDIT_MENU_ITEMS(N) _PID_EDIT_MENU_ITEMS(N); #endif diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 84bc275ce9..fd6760cbfa 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -83,7 +83,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { BACK_ITEM(MSG_BACK); ACTION_ITEM(MSG_PREHEAT_1, []{ _change_filament(ui.preheat_hotend_temp[0]); }); ACTION_ITEM(MSG_PREHEAT_2, []{ _change_filament(ui.preheat_hotend_temp[1]); }); - EDIT_ITEM_FAST(int3, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[_change_filament_extruder].target, EXTRUDE_MINTEMP, heater_maxtemp[extruder] - HOTEND_OVERSHOOT, []{ + EDIT_ITEM_FAST(int3, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[_change_filament_extruder].target, EXTRUDE_MINTEMP, thermalManager.heater_maxtemp[extruder] - HOTEND_OVERSHOOT, []{ _change_filament(thermalManager.temp_hotend[_change_filament_extruder].target); }); END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 6aa6b32659..397a320a8b 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -50,10 +50,9 @@ uint8_t MarlinUI::preheat_fan_speed[2]; void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t indb) { #if HAS_HOTEND if (indh >= 0 && ui.preheat_hotend_temp[indh] > 0) - setTargetHotend(_MIN(heater_maxtemp[e] - HOTEND_OVERSHOOT, ui.preheat_hotend_temp[indh]), e); + setTargetHotend(_MIN(thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, ui.preheat_hotend_temp[indh]), e); #else - UNUSED(e); - UNUSED(temph); + UNUSED(e); UNUSED(indh); #endif #if HAS_HEATED_BED if (indb >= 0 && ui.preheat_bed_temp[indb] > 0) setTargetBed(ui.preheat_bed_temp[indb]); @@ -166,7 +165,7 @@ void menu_temperature() { EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(0); }); #elif HAS_MULTI_HOTEND HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif #if ENABLED(SINGLENOZZLE) diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 2970130616..03d9302c64 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -121,7 +121,7 @@ void menu_tune() { EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(0); }); #elif HAS_MULTI_HOTEND HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif #if ENABLED(SINGLENOZZLE) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index a0dec77793..d27a012e45 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -142,6 +142,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #if HAS_HOTEND hotend_info_t Temperature::temp_hotend[HOTEND_TEMPS]; // = { 0 } + const int16_t Temperature::heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); #endif #if ENABLED(AUTO_POWER_E_FANS) diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index f59d894254..155644e7f8 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -322,7 +322,7 @@ class Temperature { #if HAS_HOTEND #define HOTEND_TEMPS (HOTENDS + ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)) static hotend_info_t temp_hotend[HOTEND_TEMPS]; - static constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); + static const int16_t heater_maxtemp[HOTENDS]; #endif TERN_(HAS_HEATED_BED, static bed_info_t temp_bed); TERN_(HAS_TEMP_PROBE, static probe_info_t temp_probe); From c56b66543d57d7fc7148df8891f20e30718dd491 Mon Sep 17 00:00:00 2001 From: Neil van Geffen Date: Tue, 28 Apr 2020 01:27:14 +1200 Subject: [PATCH 0301/1454] Permit Stall Sensitivity of 0 (#17722) --- Marlin/src/HAL/STM32/SoftwareSerial.cpp | 44 +++++++++---------- Marlin/src/core/multi_language.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 6 +-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 6 +-- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 6 +-- Marlin/src/pins/pins.h | 10 ++--- .../src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 6 +-- .../variants/STEVAL_F401VE/variant.cpp | 2 +- .../variants/STEVAL_F401VE/variant.h | 2 +- 9 files changed, 42 insertions(+), 42 deletions(-) diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.cpp b/Marlin/src/HAL/STM32/SoftwareSerial.cpp index f6363aa1cf..60f355e08e 100644 --- a/Marlin/src/HAL/STM32/SoftwareSerial.cpp +++ b/Marlin/src/HAL/STM32/SoftwareSerial.cpp @@ -47,49 +47,49 @@ // The order is based on (lack of) features and compare channels, we choose the simplest available // because we only need an update interrupt #if !defined(TIMER_SERIAL) -#if defined (TIM18_BASE) +#if defined(TIM18_BASE) #define TIMER_SERIAL TIM18 -#elif defined (TIM7_BASE) +#elif defined(TIM7_BASE) #define TIMER_SERIAL TIM7 -#elif defined (TIM6_BASE) +#elif defined(TIM6_BASE) #define TIMER_SERIAL TIM6 -#elif defined (TIM22_BASE) +#elif defined(TIM22_BASE) #define TIMER_SERIAL TIM22 -#elif defined (TIM21_BASE) +#elif defined(TIM21_BASE) #define TIMER_SERIAL TIM21 -#elif defined (TIM17_BASE) +#elif defined(TIM17_BASE) #define TIMER_SERIAL TIM17 -#elif defined (TIM16_BASE) +#elif defined(TIM16_BASE) #define TIMER_SERIAL TIM16 -#elif defined (TIM15_BASE) +#elif defined(TIM15_BASE) #define TIMER_SERIAL TIM15 -#elif defined (TIM14_BASE) +#elif defined(TIM14_BASE) #define TIMER_SERIAL TIM14 -#elif defined (TIM13_BASE) +#elif defined(TIM13_BASE) #define TIMER_SERIAL TIM13 -#elif defined (TIM11_BASE) +#elif defined(TIM11_BASE) #define TIMER_SERIAL TIM11 -#elif defined (TIM10_BASE) +#elif defined(TIM10_BASE) #define TIMER_SERIAL TIM10 -#elif defined (TIM12_BASE) +#elif defined(TIM12_BASE) #define TIMER_SERIAL TIM12 -#elif defined (TIM19_BASE) +#elif defined(TIM19_BASE) #define TIMER_SERIAL TIM19 -#elif defined (TIM9_BASE) +#elif defined(TIM9_BASE) #define TIMER_SERIAL TIM9 -#elif defined (TIM5_BASE) +#elif defined(TIM5_BASE) #define TIMER_SERIAL TIM5 -#elif defined (TIM4_BASE) +#elif defined(TIM4_BASE) #define TIMER_SERIAL TIM4 -#elif defined (TIM3_BASE) +#elif defined(TIM3_BASE) #define TIMER_SERIAL TIM3 -#elif defined (TIM2_BASE) +#elif defined(TIM2_BASE) #define TIMER_SERIAL TIM2 -#elif defined (TIM20_BASE) +#elif defined(TIM20_BASE) #define TIMER_SERIAL TIM20 -#elif defined (TIM8_BASE) +#elif defined(TIM8_BASE) #define TIMER_SERIAL TIM8 -#elif defined (TIM1_BASE) +#elif defined(TIM1_BASE) #define TIMER_SERIAL TIM1 #else #error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index e1cd2f308e..3533412090 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -22,7 +22,7 @@ typedef const char Language_Str[]; -#if defined(LCD_LANGUAGE_5) +#ifdef LCD_LANGUAGE_5 #define NUM_LANGUAGES 5 #elif defined(LCD_LANGUAGE_4) #define NUM_LANGUAGES 4 diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 94d90c30d1..a9d333721f 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -43,7 +43,7 @@ // // Limit Switches // -#if X_STALL_SENSITIVITY +#ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 #define X_MAX_PIN P1_28 // X+ @@ -55,7 +55,7 @@ #define X_MAX_PIN P1_28 // X+ #endif -#if Y_STALL_SENSITIVITY +#ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 #define Y_MAX_PIN P1_26 // Y+ @@ -67,7 +67,7 @@ #define Y_MAX_PIN P1_26 // Y+ #endif -#if Z_STALL_SENSITIVITY +#ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 #define Z_MAX_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 7e722ea45f..5004d166cd 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -57,7 +57,7 @@ // // Limit Switches // -#if X_STALL_SENSITIVITY +#ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 #define X_MAX_PIN P1_26 // E0DET @@ -68,7 +68,7 @@ #define X_STOP_PIN P1_29 // X-STOP #endif -#if Y_STALL_SENSITIVITY +#ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 #define Y_MAX_PIN P1_25 // E1DET @@ -79,7 +79,7 @@ #define Y_STOP_PIN P1_28 // Y-STOP #endif -#if Z_STALL_SENSITIVITY +#ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 #define Z_MAX_PIN P1_00 // PWRDET diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 8dcb194d33..f8fd0afcd3 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -58,7 +58,7 @@ // // Limit Switches // -#if X_STALL_SENSITIVITY +#ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 #define X_MAX_PIN P1_28 // X+ @@ -70,7 +70,7 @@ #define X_MAX_PIN P1_28 // X+ #endif -#if Y_STALL_SENSITIVITY +#ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 #define Y_MAX_PIN P1_26 // Y+ @@ -82,7 +82,7 @@ #define Y_MAX_PIN P1_26 // Y+ #endif -#if Z_STALL_SENSITIVITY +#ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 #define Z_MAX_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 98415e02aa..d4ba832269 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -1225,7 +1225,7 @@ // // Auto-assign pins for stallGuard sensorless homing // - #if X2_STALL_SENSITIVITY && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) + #if defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... #define X2_USE_ENDSTOP _XMIN_ @@ -1294,7 +1294,7 @@ #define Y2_SERIAL_RX_PIN _EPIN(Y2_E_INDEX, SERIAL_RX) #endif #endif - #if Y2_STALL_SENSITIVITY && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) + #if defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) #if DIAG_REMAPPED(Y2, X_MIN) #define Y2_USE_ENDSTOP _XMIN_ @@ -1362,7 +1362,7 @@ #define Z2_SERIAL_RX_PIN _EPIN(Z2_E_INDEX, SERIAL_RX) #endif #endif - #if Z2_STALL_SENSITIVITY && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) + #if defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) #if DIAG_REMAPPED(Z2, X_MIN) #define Z2_USE_ENDSTOP _XMIN_ @@ -1431,7 +1431,7 @@ #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) #endif #endif - #if Z3_STALL_SENSITIVITY && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) + #if defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) #if DIAG_REMAPPED(Z3, X_MIN) #define Z3_USE_ENDSTOP _XMIN_ @@ -1498,7 +1498,7 @@ #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX) #endif #endif - #if Z4_STALL_SENSITIVITY && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) + #if defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) #if DIAG_REMAPPED(Z4, X_MIN) #define Z4_USE_ENDSTOP _XMIN_ diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index f9e43c0043..02f2c9071b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -51,7 +51,7 @@ // // Limit Switches // -#if X_STALL_SENSITIVITY +#ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN #if X_HOME_DIR < 0 #define X_MAX_PIN PE15 // E0 @@ -63,7 +63,7 @@ #define X_MAX_PIN PE15 // E0 #endif -#if Y_STALL_SENSITIVITY +#ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_DIR < 0 #define Y_MAX_PIN PE10 // E1 @@ -75,7 +75,7 @@ #define Y_MAX_PIN PE10 // E1 #endif -#if Z_STALL_SENSITIVITY +#ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN #if Z_HOME_DIR < 0 #define Z_MAX_PIN PG5 // E2 diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.cpp b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.cpp index a53a92c48c..4ecbff0ecc 100644 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.cpp +++ b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.cpp @@ -34,7 +34,7 @@ extern "C" { #endif -#if defined(ARDUINO_STEVAL) +#ifdef ARDUINO_STEVAL // Pin number // This array allows to wrap Arduino pin number(Dx or x) // to STM32 PinName (PX_n) diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h index 571f3207e9..df7295ab17 100644 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h +++ b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/variant.h @@ -41,7 +41,7 @@ extern "C" { /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ -#if defined(ARDUINO_STEVAL) +#ifdef ARDUINO_STEVAL /*---------------------------------------------------------------------------- From 7eac76d31bd437f62abf82f82417ccc3938681ed Mon Sep 17 00:00:00 2001 From: Warboy1982 Date: Mon, 27 Apr 2020 23:38:23 +1000 Subject: [PATCH 0302/1454] Patch BLTouch Z_MAX_PIN for GT2560 Rev.A (non-plus) (#17721) --- Marlin/src/pins/mega/pins_GT2560_REV_A.h | 12 +++++++++++- Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h | 4 +--- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index e111f2ce44..885751d319 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -44,7 +44,17 @@ #define Y_MIN_PIN 26 #define Y_MAX_PIN 28 #define Z_MIN_PIN 30 -#define Z_MAX_PIN 32 + +#if ENABLED(BLTOUCH) + #if MB(GT2560_REV_A_PLUS) + #define SERVO0_PIN 11 + #else + #define SERVO0_PIN 32 + #endif + #define Z_MAX_PIN -1 +#else + #define Z_MAX_PIN 32 +#endif // // Steppers diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h index 3ce4627dce..1a9fcfd270 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h @@ -29,8 +29,6 @@ #include "pins_GT2560_REV_A.h" -#if ENABLED(BLTOUCH) - #define SERVO0_PIN 11 -#else +#if DISABLED(BLTOUCH) #define SERVO0_PIN 32 #endif From 267c25fd536f7a131764c073508be2b4c0a534d6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 09:05:41 -0500 Subject: [PATCH 0303/1454] Remove spurious brace Followup to c536b8de62 --- Marlin/src/lcd/menu/menu_info.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 1b52c182ba..2f6ab974f4 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -180,7 +180,6 @@ void menu_info_thermistors() { #endif #if HAS_HEATED_BED - { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_BED #include "../thermistornames.h" From 9b90dfaa482182d964d291ad226e3123f612f266 Mon Sep 17 00:00:00 2001 From: grauerfuchs <42082416+grauerfuchs@users.noreply.github.com> Date: Mon, 27 Apr 2020 10:26:45 -0400 Subject: [PATCH 0304/1454] Fix draw_temps missing define compile (#17750) --- Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 0342d73607..9338ab82e8 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -579,7 +579,7 @@ void ST7920_Lite_Status_Screen::draw_extruder_2_temp(const int16_t temp, const i #if HAS_HEATED_BED void ST7920_Lite_Status_Screen::draw_bed_temp(const int16_t temp, const int16_t target, bool forceUpdate) { const bool show_target = target && FAR(temp, target); - draw_temps(HAS_MULTI_HOTEND ? 2 : 1, temp, target, show_target, display_state.bed_show_target != show_target || forceUpdate); + draw_temps(TERN(HAS_MULTI_HOTEND, 2, 1), temp, target, show_target, display_state.bed_show_target != show_target || forceUpdate); display_state.bed_show_target = show_target; } #endif From 035d6cd16d8edcbc76d8a1aa4a1d2e2e3cde60ba Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 09:42:51 -0500 Subject: [PATCH 0305/1454] Patch i2c, info menu --- Marlin/src/HAL/HAL.h | 4 ++++ Marlin/src/HAL/LPC1768/HAL.h | 3 +++ Marlin/src/core/macros.h | 2 +- Marlin/src/lcd/menu/menu_info.cpp | 11 ++--------- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index 2e024878ff..614c6cbaf9 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -27,6 +27,10 @@ #define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION) +#ifndef I2C_ADDRESS + #define I2C_ADDRESS(A) (A) +#endif + inline void watchdog_refresh() { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); } diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 70bb50e692..2d385fd16c 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -48,6 +48,9 @@ extern "C" volatile uint32_t _millis; #include #include +// i2c uses 8-bit shifted address +#define I2C_ADDRESS(A) ((A) << 1) + // // Default graphical display delays // diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 214539d830..c84d7b8116 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -292,7 +292,7 @@ #define FMOD(x, y) fmodf(x, y) #define HYPOT(x,y) SQRT(HYPOT2(x,y)) -#define I2C_ADDRESS(A) int(TERN(TARGET_LPC1768, (A) << 1, A)) +#define I2C_ADDRESS(A) (typeof(A))(TERN(TARGET_LPC1768, (A) << 1, A)) // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 2f6ab974f4..41baa5d2e0 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -34,8 +34,8 @@ #include "game/game.h" #endif -#define VALUE_ITEM(MSG, VALUE, STYL) do{ strcpy_P(buffer, PSTR(": ")); strcpy(buffer + 2, VALUE); STATIC_ITEM(MSG, STYL, buffer); }while(0) -#define VALUE_ITEM_P(MSG, PVALUE, STYL) do{ strcpy_P(buffer, PSTR(": ")); strcpy_P(buffer + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, buffer); }while(0) +#define VALUE_ITEM(MSG, VALUE, STYL) do{ char buffer[21]; strcpy_P(buffer, PSTR(": ")); strcpy(buffer + 2, VALUE); STATIC_ITEM(MSG, STYL, buffer); }while(0) +#define VALUE_ITEM_P(MSG, PVALUE, STYL) do{ char buffer[21]; strcpy_P(buffer, PSTR(": ")); strcpy_P(buffer + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, buffer); }while(0) #if ENABLED(PRINTCOUNTER) @@ -51,8 +51,6 @@ printStatistics stats = print_job_timer.getStats(); - char buffer[21]; - START_SCREEN(); // 12345678901234567890 VALUE_ITEM(MSG_INFO_PRINT_COUNT, i16tostr3left(stats.totalPrints), SS_LEFT); // Print Count: 999 VALUE_ITEM(MSG_INFO_COMPLETED_PRINTS, i16tostr3left(stats.finishedPrints), SS_LEFT); // Completed : 666 @@ -100,8 +98,6 @@ void menu_info_thermistors() { if (ui.use_click()) return ui.go_back(); - char buffer[21]; // For macro usage - START_SCREEN(); #if EXTRUDERS @@ -208,8 +204,6 @@ void menu_info_thermistors() { void menu_info_board() { if (ui.use_click()) return ui.go_back(); - char buffer[21]; // For macro usage - START_SCREEN(); STATIC_ITEM_P(PSTR(BOARD_INFO_NAME), SS_CENTER|SS_INVERT); // MyPrinterController #ifdef BOARD_WEBSITE_URL @@ -248,7 +242,6 @@ void menu_info_board() { STATIC_ITEM_P(PSTR(STRING_DISTRIBUTION_DATE)); // YYYY-MM-DD HH:MM STATIC_ITEM_P(PSTR(MACHINE_NAME)); // My3DPrinter STATIC_ITEM_P(PSTR(WEBSITE_URL)); // www.my3dprinter.com - char buffer[21]; VALUE_ITEM_P(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); // Extruders: 2 #if ENABLED(AUTO_BED_LEVELING_3POINT) STATIC_ITEM(MSG_3POINT_LEVELING); // 3-Point Leveling From 0b3a96412ccbee8e4a3caeb0edd950852280440d Mon Sep 17 00:00:00 2001 From: RudolphRiedel <31180093+RudolphRiedel@users.noreply.github.com> Date: Mon, 27 Apr 2020 17:14:42 +0200 Subject: [PATCH 0306/1454] Fixes for ExtUI / EVE (#17726) --- Marlin/Configuration_adv.h | 1 + .../ftdi_eve_lib/basic/commands.cpp | 41 ++++++++++++------- .../ftdi_eve_lib/basic/spi.h | 2 +- .../lib/ftdi_eve_touch_ui/pin_mappings.h | 18 ++++++++ .../screens/interface_settings_screen.cpp | 2 +- 5 files changed, 48 insertions(+), 16 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7a125b06d7..fb82aed698 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1385,6 +1385,7 @@ //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping + //#define CHEETAH_TFT_PINMAP // FYSETC Cheetah pin mapping //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, FYSETC Cheetah and Stock boards) EXP1 pin mapping //#define GENERIC_EXP2_PINMAP // GENERIC EXP2 pin mapping diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 1c297d6acd..9780ebe858 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -1057,6 +1057,8 @@ void CLCD::init() { host_cmd(Use_Crystal ? CLKEXT : CLKINT, 0); host_cmd(FTDI::ACTIVE, 0); // Activate the System Clock + delay(40); // FTDI/BRT recommendation: no SPI traffic during startup. EVE needs at the very least 45ms to start, so leave her alone for a little while. + /* read the device-id until it returns 0x7c or times out, should take less than 150ms */ uint8_t counter; for (counter = 0; counter < 250; counter++) { @@ -1078,6 +1080,24 @@ void CLCD::init() { } } + /* make sure that all units are in working conditions, usually the touch-controller needs a little more time */ + for (counter = 0; counter < 100; counter++) { + uint8_t reset_status = mem_read_8(REG::CPURESET) & 0x03; + if (reset_status == 0x00) { + #if ENABLED(TOUCH_UI_DEBUG) + SERIAL_ECHO_MSG("FTDI chip all units running "); + #endif + break; + } + else + delay(1); + + if (ENABLED(TOUCH_UI_DEBUG) && counter == 99) { + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR("Timeout waiting for reset status. Should be 0x00, got ", reset_status); + } + } + mem_write_8(REG::PWM_DUTY, 0); // turn off Backlight, Frequency already is set to 250Hz default /* Configure the FT8xx Registers */ @@ -1129,9 +1149,6 @@ void CLCD::init() { // Turning off dithering seems to help prevent horizontal line artifacts on certain colors mem_write_8(REG::DITHER, 0); - // Initialize the command FIFO - CommandFifo::reset(); - default_touch_transform(); default_display_orientation(); } @@ -1151,17 +1168,13 @@ void CLCD::default_display_orientation() { #if FTDI_API_LEVEL >= 810 // Set the initial display orientation. On the FT810, we use the command // processor to do this since it will also update the transform matrices. - if (FTDI::ftdi_chip >= 810) { - CommandFifo cmd; - cmd.setrotate( - ENABLED(TOUCH_UI_MIRRORED) * 4 - + ENABLED(TOUCH_UI_PORTRAIT) * 2 - + ENABLED(TOUCH_UI_INVERTED) * 1 - ); - cmd.execute(); - } - else - TERN_(TOUCH_UI_INVERTED, mem_write_32(REG::ROTATE, 1)); + CommandFifo cmd; + cmd.setrotate( + ENABLED(TOUCH_UI_MIRRORED) * 4 + + ENABLED(TOUCH_UI_PORTRAIT) * 2 + + ENABLED(TOUCH_UI_INVERTED) * 1 + ); + cmd.execute(); #elif ANY(TOUCH_UI_PORTRAIT, TOUCH_UI_MIRRORED) #error "PORTRAIT or MIRRORED orientation not supported on the FT800." #elif ENABLED(TOUCH_UI_INVERTED) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h index 763f5ccb1d..9f6c123179 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h @@ -55,7 +55,7 @@ namespace FTDI { #ifdef CLCD_USE_SOFT_SPI return _soft_spi_xfer(0x00); #else - SPI_OBJ.transfer(0x00); + return SPI_OBJ.transfer(0x00); #endif }; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 21f4769bea..ed9affba23 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -27,6 +27,24 @@ * without adding new pin definitions to the board. */ +#ifdef CHEETAH_TFT_PINMAP + #ifndef __MARLIN_FIRMWARE__ + #error "This pin mapping requires Marlin." + #endif + + #define CLCD_SPI_BUS 2 + + #define CLCD_MOD_RESET PC9 + #define CLCD_SPI_CS PB12 + + //#define CLCD_USE_SOFT_SPI + #if ENABLED(CLCD_USE_SOFT_SPI) + #define CLCD_SOFT_SPI_MOSI PB15 + #define CLCD_SOFT_SPI_MISO PB14 + #define CLCD_SOFT_SPI_SCLK PB13 + #endif +#endif + #ifdef S6_TFT_PINMAP #ifndef __MARLIN_FIRMWARE__ #error "This pin mapping requires Marlin." diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index b04cfae7fc..0026478f7b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -161,7 +161,7 @@ void InterfaceSettingsScreen::onIdle() { CommandProcessor cmd; switch (cmd.track_tag(value)) { case 2: - screen_data.InterfaceSettingsScreen.brightness = _MAX(11, (value * 128UL) / 0xFFFF); + screen_data.InterfaceSettingsScreen.brightness = max(11, (value * 128UL) / 0xFFFF); CLCD::set_brightness(screen_data.InterfaceSettingsScreen.brightness); SaveSettingsDialogBox::settingsChanged(); break; From 66676e6dd422f0518102be5375648a68d4de07c8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 10:19:01 -0500 Subject: [PATCH 0307/1454] Remove extra macro --- Marlin/src/core/macros.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index c84d7b8116..88a807c570 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -292,8 +292,6 @@ #define FMOD(x, y) fmodf(x, y) #define HYPOT(x,y) SQRT(HYPOT2(x,y)) -#define I2C_ADDRESS(A) (typeof(A))(TERN(TARGET_LPC1768, (A) << 1, A)) - // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT #define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) From cd2652b2fc7efe7b38077453f81051f23928d2e5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 28 Apr 2020 00:17:17 +0000 Subject: [PATCH 0308/1454] [cron] Bump distribution date (2020-04-28) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 1c1a54cd68..6cb2ec6e23 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-27" + #define STRING_DISTRIBUTION_DATE "2020-04-28" #endif /** From f6e820b4e94ea47f558d13009ae9120888c9d694 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 21:03:55 -0500 Subject: [PATCH 0309/1454] Fix buffer stuff --- Marlin/src/lcd/menu/menu_info.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 41baa5d2e0..f8df26bf08 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -51,6 +51,8 @@ printStatistics stats = print_job_timer.getStats(); + char buffer[21]; + START_SCREEN(); // 12345678901234567890 VALUE_ITEM(MSG_INFO_PRINT_COUNT, i16tostr3left(stats.totalPrints), SS_LEFT); // Print Count: 999 VALUE_ITEM(MSG_INFO_COMPLETED_PRINTS, i16tostr3left(stats.finishedPrints), SS_LEFT); // Completed : 666 From 94291eb59fa7696009be8eafd5d0f8348c286ad5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 22:26:31 -0500 Subject: [PATCH 0310/1454] Clean up old externs / includes --- Marlin/src/MarlinCore.h | 10 ---------- Marlin/src/module/stepper/L64xx.h | 14 +++++++------- 2 files changed, 7 insertions(+), 17 deletions(-) diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 3f8b72b88a..7f6d4432db 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -31,11 +31,6 @@ #include #include -#if HAS_L64XX - #include "libs/L64XX/L64XX_Marlin.h" - extern uint8_t axis_known_position; -#endif - void stop(); // Pass true to keep steppers from timing out @@ -95,10 +90,6 @@ extern bool wait_for_heatup; // Inactivity shutdown timer extern millis_t max_inactive_time, stepper_inactive_time; -#if ENABLED(USE_CONTROLLER_FAN) - extern uint8_t controllerfan_speed; -#endif - #if ENABLED(PSU_CONTROL) extern bool powersupply_on; #define PSU_PIN_ON() do{ OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_HIGH); powersupply_on = true; }while(0) @@ -127,4 +118,3 @@ void protected_pin_err(); extern const char NUL_STR[], M112_KILL_STR[], G28_STR[], M21_STR[], M23_STR[], M24_STR[], SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[], X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[]; - diff --git a/Marlin/src/module/stepper/L64xx.h b/Marlin/src/module/stepper/L64xx.h index 4449618e0b..ca2358b967 100644 --- a/Marlin/src/module/stepper/L64xx.h +++ b/Marlin/src/module/stepper/L64xx.h @@ -221,7 +221,7 @@ #define E0_DIR_WRITE(STATE) L64XX_DIR_WRITE(E0, STATE) #define E0_DIR_READ() (stepper##E0.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E0(L6470) - #define DISABLE_STEPPER_E0() do{ stepperE0.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E0() do{ stepperE0.free(); }while(0) #endif #endif #endif @@ -241,7 +241,7 @@ #define E1_DIR_WRITE(STATE) L64XX_DIR_WRITE(E1, STATE) #define E1_DIR_READ() (stepper##E1.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E1(L6470) - #define DISABLE_STEPPER_E1() do{ stepperE1.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E1() do{ stepperE1.free(); }while(0) #endif #endif #endif @@ -261,7 +261,7 @@ #define E2_DIR_WRITE(STATE) L64XX_DIR_WRITE(E2, STATE) #define E2_DIR_READ() (stepper##E2.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E2(L6470) - #define DISABLE_STEPPER_E2() do{ stepperE2.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E2() do{ stepperE2.free(); }while(0) #endif #endif #endif @@ -298,7 +298,7 @@ #define E4_DIR_WRITE(STATE) L64XX_DIR_WRITE(E4, STATE) #define E4_DIR_READ() (stepper##E4.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E4(L6470) - #define DISABLE_STEPPER_E4() do{ stepperE4.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E4() do{ stepperE4.free(); }while(0) #endif #endif #endif @@ -318,7 +318,7 @@ #define E5_DIR_WRITE(STATE) L64XX_DIR_WRITE(E5, STATE) #define E5_DIR_READ() (stepper##E5.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E5(L6470) - #define DISABLE_STEPPER_E5() do{ stepperE5.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E5() do{ stepperE5.free(); }while(0) #endif #endif #endif @@ -338,7 +338,7 @@ #define E6_DIR_WRITE(STATE) L64XX_DIR_WRITE(E6, STATE) #define E6_DIR_READ() (stepper##E6.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E6(L6470) - #define DISABLE_STEPPER_E6() do{ stepperE6.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E6() do{ stepperE6.free(); }while(0) #endif #endif #endif @@ -358,7 +358,7 @@ #define E7_DIR_WRITE(STATE) L64XX_DIR_WRITE(E7, STATE) #define E7_DIR_READ() (stepper##E7.getStatus() & STATUS_DIR); #if AXIS_DRIVER_TYPE_E7(L6470) - #define DISABLE_STEPPER_E7() do{ stepperE7.free(); CBI(axis_known_position, E_AXIS); }while(0) + #define DISABLE_STEPPER_E7() do{ stepperE7.free(); }while(0) #endif #endif #endif From 01c646a892c9cd36baf577ca9be344e3490a7727 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 22:35:25 -0500 Subject: [PATCH 0311/1454] Apply more HAS_HOTEND --- Marlin/src/feature/power.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 76 +++++++---------------- Marlin/src/module/configuration_store.cpp | 8 +-- Marlin/src/module/temperature.cpp | 4 +- 9 files changed, 34 insertions(+), 66 deletions(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index add3e1d8aa..71c0f1facb 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -74,7 +74,7 @@ bool Power::is_power_needed() { HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0) return true; if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) return true; - #if HOTENDS && AUTO_POWER_E_TEMP + #if HAS_HOTEND && AUTO_POWER_E_TEMP HOTEND_LOOP() if (thermalManager.degHotend(e) >= AUTO_POWER_E_TEMP) return true; #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index a6f54ee022..de6fe29e6a 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -544,7 +544,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 120: M120(); break; // M120: Enable endstops case 121: M121(); break; // M121: Disable endstops - #if HOTENDS && HAS_LCD_MENU + #if HAS_HOTEND && HAS_LCD_MENU case 145: M145(); break; // M145: Set material heatup parameters #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 6a4a7af985..37521e8769 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -602,7 +602,7 @@ private: static void M191(); #endif - #if HOTENDS && HAS_LCD_MENU + #if HAS_HOTEND && HAS_LCD_MENU static void M145(); #endif diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index feac437c6c..15ff541739 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if HOTENDS && HAS_LCD_MENU +#if HAS_HOTEND && HAS_LCD_MENU #include "../gcode.h" #include "../../lcd/ultralcd.h" diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 5635453b64..5d5d4321a9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1653,7 +1653,7 @@ #define HAS_TEMP_ADC_CHAMBER 1 #endif -#if HOTENDS && EITHER(HAS_TEMP_ADC_0, HEATER_0_USES_MAX6675) +#if HAS_HOTEND && EITHER(HAS_TEMP_ADC_0, HEATER_0_USES_MAX6675) #define HAS_TEMP_HOTEND 1 #endif #define HAS_TEMP_BED HAS_TEMP_ADC_BED diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 6583a767d9..1095a97c0e 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -1749,7 +1749,7 @@ #if HAS_FAN0 && STATUS_FAN_WIDTH && HOTENDS <= 4 && defined(STATUS_FAN_FRAMES) #define DO_DRAW_FAN 1 #endif -#if HOTENDS && ENABLED(STATUS_HOTEND_ANIM) +#if BOTH(HAS_HOTEND, STATUS_HOTEND_ANIM) #define ANIM_HOTEND 1 #endif #if BOTH(DO_DRAW_BED, STATUS_BED_ANIM) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index ab5aa887e7..a9536c68cd 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -169,7 +169,7 @@ namespace ExtUI { } void enableHeater(const extruder_t extruder) { - #if HOTENDS && HEATER_IDLE_HANDLER + #if HAS_HOTEND && HEATER_IDLE_HANDLER thermalManager.reset_hotend_idle_timer(extruder - E0); #else UNUSED(extruder); @@ -234,7 +234,7 @@ namespace ExtUI { bool isHeaterIdle(const extruder_t extruder) { return false - #if HOTENDS && HEATER_IDLE_HANDLER + #if HAS_HOTEND && HEATER_IDLE_HANDLER || thermalManager.hotend_idle[extruder - E0].timed_out #else ; UNUSED(extruder) @@ -746,13 +746,13 @@ namespace ExtUI { #endif float getZOffset_mm() { - #if HAS_BED_PROBE - return probe.offset.z; - #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) - return (planner.steps_to_mm[Z_AXIS] * babystep.axis_total[BS_AXIS_IND(Z_AXIS)]); - #else - return 0.0; - #endif + return (0.0f + #if HAS_BED_PROBE + + probe.offset.z + #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) + + planner.steps_to_mm[Z_AXIS] * babystep.axis_total[BS_AXIS_IND(Z_AXIS)] + #endif + ); } void setZOffset_mm(const float value) { @@ -857,17 +857,9 @@ namespace ExtUI { float getFeedrate_percent() { return feedrate_percentage; } #if ENABLED(PIDTEMP) - float getPIDValues_Kp(const extruder_t tool) { - return PID_PARAM(Kp, tool); - } - - float getPIDValues_Ki(const extruder_t tool) { - return unscalePID_i(PID_PARAM(Ki, tool)); - } - - float getPIDValues_Kd(const extruder_t tool) { - return unscalePID_d(PID_PARAM(Kd, tool)); - } + float getPIDValues_Kp(const extruder_t tool) { return PID_PARAM(Kp, tool); } + float getPIDValues_Ki(const extruder_t tool) { return unscalePID_i(PID_PARAM(Ki, tool)); } + float getPIDValues_Kd(const extruder_t tool) { return unscalePID_d(PID_PARAM(Kd, tool)); } void setPIDValues(const float p, const float i, const float d, extruder_t tool) { thermalManager.temp_hotend[tool].pid.Kp = p; @@ -876,23 +868,15 @@ namespace ExtUI { thermalManager.updatePID(); } - void startPIDTune(const float temp, extruder_t tool){ + void startPIDTune(const float temp, extruder_t tool) { thermalManager.PID_autotune(temp, (heater_ind_t)tool, 8, true); } #endif #if ENABLED(PIDTEMPBED) - float getBedPIDValues_Kp() { - return thermalManager.temp_bed.pid.Kp; - } - - float getBedPIDValues_Ki() { - return unscalePID_i(thermalManager.temp_bed.pid.Ki); - } - - float getBedPIDValues_Kd() { - return unscalePID_d(thermalManager.temp_bed.pid.Kd); - } + float getBedPIDValues_Kp() { return thermalManager.temp_bed.pid.Kp; } + float getBedPIDValues_Ki() { return unscalePID_i(thermalManager.temp_bed.pid.Ki); } + float getBedPIDValues_Kd() { return unscalePID_d(thermalManager.temp_bed.pid.Kd); } void setBedPIDValues(const float p, const float i, const float d) { thermalManager.temp_bed.pid.Kp = p; @@ -906,20 +890,12 @@ namespace ExtUI { } #endif - void injectCommands_P(PGM_P const gcode) { - queue.inject_P(gcode); - } + void injectCommands_P(PGM_P const gcode) { queue.inject_P(gcode); } bool commandsInQueue() { return (planner.movesplanned() || queue.has_commands_queued()); } - bool isAxisPositionKnown(const axis_t axis) { - return TEST(axis_known_position, axis); - } - - bool isAxisPositionKnown(const extruder_t) { - return TEST(axis_known_position, E_AXIS); - } - + bool isAxisPositionKnown(const axis_t axis) { return TEST(axis_known_position, axis); } + bool isAxisPositionKnown(const extruder_t) { return TEST(axis_known_position, E_AXIS); } bool isPositionKnown() { return all_axes_known(); } bool isMachineHomed() { return all_axes_homed(); } @@ -1008,17 +984,9 @@ namespace ExtUI { return IFSD(IS_SD_INSERTED() && card.isMounted(), false); } - void pausePrint() { - ui.pause_print(); - } - - void resumePrint() { - ui.resume_print(); - } - - void stopPrint() { - ui.abort_print(); - } + void pausePrint() { ui.pause_print(); } + void resumePrint() { ui.resume_print(); } + void stopPrint() { ui.abort_print(); } void onUserConfirmRequired_P(PGM_P const pstr) { char msg[strlen_P(pstr) + 1]; diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index ea324731c5..1582cf7067 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -799,7 +799,7 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(ui_preheat_hotend_temp); - #if HOTENDS && HAS_LCD_MENU + #if HAS_HOTEND && HAS_LCD_MENU const int16_t (&ui_preheat_hotend_temp)[2] = ui.preheat_hotend_temp, (&ui_preheat_bed_temp)[2] = ui.preheat_bed_temp; const uint8_t (&ui_preheat_fan_speed)[2] = ui.preheat_fan_speed; @@ -1649,7 +1649,7 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(ui_preheat_hotend_temp); - #if HOTENDS && HAS_LCD_MENU + #if HAS_HOTEND && HAS_LCD_MENU int16_t (&ui_preheat_hotend_temp)[2] = ui.preheat_hotend_temp, (&ui_preheat_bed_temp)[2] = ui.preheat_bed_temp; uint8_t (&ui_preheat_fan_speed)[2] = ui.preheat_fan_speed; @@ -2557,7 +2557,7 @@ void MarlinSettings::reset() { // Preheat parameters // - #if HOTENDS && HAS_LCD_MENU + #if HAS_HOTEND && HAS_LCD_MENU ui.preheat_hotend_temp[0] = PREHEAT_1_TEMP_HOTEND; ui.preheat_hotend_temp[1] = PREHEAT_2_TEMP_HOTEND; ui.preheat_bed_temp[0] = PREHEAT_1_TEMP_BED; @@ -3077,7 +3077,7 @@ void MarlinSettings::reset() { #endif // [XYZ]_DUAL_ENDSTOPS - #if HOTENDS && HAS_LCD_MENU + #if HAS_HOTEND && HAS_LCD_MENU CONFIG_ECHO_HEADING("Material heatup parameters:"); LOOP_L_N(i, COUNT(ui.preheat_hotend_temp)) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index d27a012e45..e55dcb074b 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2386,7 +2386,7 @@ void Temperature::tick() { #if DISABLED(SLOW_PWM_HEATERS) - #if HOTENDS || HAS_HEATED_BED || HAS_HEATED_CHAMBER + #if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER constexpr uint8_t pwm_mask = #if ENABLED(SOFT_PWM_DITHER) _BV(SOFT_PWM_SCALE) - 1 @@ -2931,7 +2931,7 @@ void Temperature::tick() { #endif // AUTO_REPORT_TEMPERATURES - #if HOTENDS && HAS_DISPLAY + #if HAS_HOTEND && HAS_DISPLAY void Temperature::set_heating_message(const uint8_t e) { const bool heating = isHeatingHotend(e); ui.status_printf_P(0, From 919e53a5d4f8831f47021a687d4cc7f1705494f8 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 27 Apr 2020 21:43:42 -0600 Subject: [PATCH 0312/1454] Fix: SD pause broken with PARK_HEAD_ON_PAUSE (#17754) --- Marlin/src/gcode/sd/M24_M25.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index ea1252885c..8ac3f45491 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -82,17 +82,17 @@ void GcodeSuite::M24() { */ void GcodeSuite::M25() { - // Set initial pause flag to prevent more commands from landing in the queue while we try to pause - #if ENABLED(SDSUPPORT) - if (IS_SD_PRINTING()) card.pauseSDPrint(); - #endif - #if ENABLED(PARK_HEAD_ON_PAUSE) M125(); #else + // Set initial pause flag to prevent more commands from landing in the queue while we try to pause + #if ENABLED(SDSUPPORT) + if (IS_SD_PRINTING()) card.pauseSDPrint(); + #endif + #if ENABLED(POWER_LOSS_RECOVERY) if (recovery.enabled) recovery.save(true); #endif From 630b4ecfff2eb3f345bf5c9d4050040417a01227 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 22:59:12 -0500 Subject: [PATCH 0313/1454] Patch XY frequency menu --- Marlin/src/lcd/menu/menu_advanced.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index e510a8f339..eac83c1d11 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -412,8 +412,8 @@ void menu_cancelobject(); #endif #ifdef XY_FREQUENCY_LIMIT - EDIT_ITEM(uint16_3, MSG_XY_FREQUENCY_LIMIT, &planner.xy_freq_limit_hz, 0, 100, refresh_frequency_limit(), true); - editable.uint8 = ROUND(planner.xy_freq_min_speed_factor * 255 * 100); // percent to u8 + EDIT_ITEM(int8, MSG_XY_FREQUENCY_LIMIT, &planner.xy_freq_limit_hz, 0, 100, planner.refresh_frequency_limit, true); + editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255 * 100)); // percent to u8 EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); #endif From 9fa5119333e47bf56075eae09f4972ca06f0ce3f Mon Sep 17 00:00:00 2001 From: FilippoR Date: Tue, 28 Apr 2020 06:35:10 +0200 Subject: [PATCH 0314/1454] Block during move in UBL mesh edit (#17670) --- Marlin/src/lcd/menu/menu_ubl.cpp | 23 +++++------------------ 1 file changed, 5 insertions(+), 18 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index b3579d3538..683470c782 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -437,16 +437,10 @@ void ubl_map_move_to_xy() { void set_current_from_steppers_for_axis(const AxisEnum axis); void sync_plan_position(); -void _lcd_hard_stop() { - const screenFunc_t old_screen = ui.currentScreen; - lcd_limbo(); - planner.quick_stop(); - ui.currentScreen = old_screen; - set_current_from_steppers_for_axis(ALL_AXES); - sync_plan_position(); -} - void _lcd_ubl_output_map_lcd() { + + if (planner.movesplanned()) return; + static int16_t step_scaler = 0; if (ui.use_click()) return _lcd_ubl_map_lcd_edit_cmd(); @@ -458,11 +452,7 @@ void _lcd_ubl_output_map_lcd() { ui.refresh(LCDVIEW_REDRAW_NOW); } - #if IS_KINEMATIC - #define KEEP_LOOPING true // Loop until a valid point is found - #else - #define KEEP_LOOPING false - #endif + #define KEEP_LOOPING ENABLED(IS_KINEMATIC) // Loop until a valid point is found do { // Encoder to the right (++) @@ -495,10 +485,6 @@ void _lcd_ubl_output_map_lcd() { if (ui.should_draw()) { ui.ubl_plot(x_plot, y_plot); - - if (planner.movesplanned()) // If the nozzle is already moving, cancel the move. - _lcd_hard_stop(); - ubl_map_move_to_xy(); // Move to new location } } @@ -511,6 +497,7 @@ void _lcd_ubl_output_map_lcd_cmd() { set_all_unhomed(); queue.inject_P(G28_STR); } + if (planner.movesplanned()) return; ui.goto_screen(_lcd_ubl_map_homing); } From f709c565a1782111d464f1b0659d7b46a12a497d Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 27 Apr 2020 21:45:20 -0700 Subject: [PATCH 0315/1454] STM32F1: SD EEPROM fallback (#17715) --- .github/workflows/test-builds.yml | 2 +- Marlin/src/HAL/STM32/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/STM32/inc/SanityCheck.h | 8 +++ Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp | 53 ++++++++----------- .../src/HAL/STM32F1/inc/Conditionals_post.h | 5 ++ Marlin/src/HAL/STM32F1/inc/SanityCheck.h | 8 +++ buildroot/share/tests/mks_robin_lite-tests | 10 ++-- 7 files changed, 50 insertions(+), 38 deletions(-) diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 29105c4ddc..f08032c2de 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -58,6 +58,7 @@ jobs: - ARMED - FYSETC_S6 - malyan_M300 + - mks_robin_lite # Put lengthy tests last @@ -75,7 +76,6 @@ jobs: #- at90usb1286_cdc #- at90usb1286_dfu #- STM32F103CB_malyan - #- mks_robin_lite #- mks_robin_mini #- mks_robin_nano diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index 11603c9ef4..32ad3a57b9 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index b1d0029ba9..9cd8db81f4 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -35,3 +35,11 @@ #if ENABLED(FAST_PWM_FAN) #error "FAST_PWM_FAN is not yet implemented for this platform." #endif + +#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) + #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise + #if USE_FALLBACK_EEPROM + #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." + #endif + #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." +#endif diff --git a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp index 7894e69787..bfa9b78dc9 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp @@ -32,6 +32,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) #include "../shared/eeprom_api.h" +#include "../../sd/cardreader.h" #ifndef E2END #define E2END 0xFFF // 4KB @@ -41,44 +42,34 @@ #define _ALIGN(x) __attribute__ ((aligned(x))) // SDIO uint32_t* compat. static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE]; -#if ENABLED(SDSUPPORT) +#define EEPROM_FILENAME "eeprom.dat" - #include "../../sd/cardreader.h" +bool PersistentStore::access_start() { + if (!card.isMounted()) return false; - #define EEPROM_FILENAME "eeprom.dat" + SdFile file, root = card.getroot(); + if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) + return true; // false aborts the save - bool PersistentStore::access_start() { - if (!card.isMounted()) return false; + int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE); + if (bytes_read < 0) return false; + for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++) + HAL_eeprom_data[bytes_read] = 0xFF; + file.close(); + return true; +} - SdFile file, root = card.getroot(); - if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) - return true; // false aborts the save +bool PersistentStore::access_finish() { + if (!card.isMounted()) return false; - int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE); - if (bytes_read < 0) return false; - for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++) - HAL_eeprom_data[bytes_read] = 0xFF; + SdFile file, root = card.getroot(); + int bytes_written = 0; + if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { + bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE); file.close(); - return true; } - - bool PersistentStore::access_finish() { - if (!card.isMounted()) return false; - - SdFile file, root = card.getroot(); - int bytes_written = 0; - if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { - bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE); - file.close(); - } - return (bytes_written == HAL_EEPROM_SIZE); - } - -#else // !SDSUPPORT - - #error "Please define SPI_EEPROM (in Configuration.h) or disable EEPROM_SETTINGS." - -#endif // !SDSUPPORT + return (bytes_written == HAL_EEPROM_SIZE); +} bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { for (size_t i = 0; i < size; i++) diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h index 0285c52ee3..32ad3a57b9 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h @@ -20,3 +20,8 @@ * */ #pragma once + +// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation +#if USE_FALLBACK_EEPROM + #define SDCARD_EEPROM_EMULATION +#endif diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index b8ebc446d6..33365fab4b 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -41,3 +41,11 @@ #warning "With TMC2208/9 consider using SoftwareSerialM with HAVE_SW_SERIAL and appropriate SS_TIMER." #error "Missing SoftwareSerial implementation." #endif + +#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) + #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise + #if USE_FALLBACK_EEPROM + #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." + #endif + #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." +#endif diff --git a/buildroot/share/tests/mks_robin_lite-tests b/buildroot/share/tests/mks_robin_lite-tests index a50d7347f5..34809641ec 100644 --- a/buildroot/share/tests/mks_robin_lite-tests +++ b/buildroot/share/tests/mks_robin_lite-tests @@ -6,12 +6,12 @@ # exit on first failure set -e -use_example_configs Mks/Robin +restore_configs opt_set MOTHERBOARD BOARD_MKS_ROBIN_LITE -opt_set EXTRUDERS 1 -opt_set TEMP_SENSOR_1 0 -opt_disable FSMC_GRAPHICAL_TFT -exec_test $1 $2 "Default Configuration" +opt_set SERIAL_PORT -1 +opt_enable EEPROM_SETTINGS +opt_enable SDSUPPORT +exec_test $1 $2 "Default Configuration with Fallback SD EEPROM" # cleanup restore_configs From 4f003fc7a715830da7324da2c90f8411df3b1efc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Apr 2020 23:52:11 -0500 Subject: [PATCH 0316/1454] Streamline menu item logic (#17664) --- Marlin/src/lcd/menu/menu.h | 39 +++++++++- Marlin/src/lcd/menu/menu_advanced.cpp | 81 +++++++++++--------- Marlin/src/lcd/menu/menu_bed_corners.cpp | 21 ++--- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 18 +++-- Marlin/src/lcd/menu/menu_cancelobject.cpp | 14 ++-- Marlin/src/lcd/menu/menu_configuration.cpp | 16 ++-- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 4 +- Marlin/src/lcd/menu/menu_filament.cpp | 77 ++++++++++--------- Marlin/src/lcd/menu/menu_info.cpp | 59 +++++++------- Marlin/src/lcd/menu/menu_led.cpp | 6 +- Marlin/src/lcd/menu/menu_main.cpp | 69 +++++++++-------- Marlin/src/lcd/menu/menu_media.cpp | 23 +----- Marlin/src/lcd/menu/menu_motion.cpp | 59 +++++++------- Marlin/src/lcd/menu/menu_spindle_laser.cpp | 15 ++-- Marlin/src/lcd/menu/menu_temperature.cpp | 28 ++++--- Marlin/src/lcd/menu/menu_tune.cpp | 18 +++-- Marlin/src/lcd/menu/menu_ubl.cpp | 7 +- 17 files changed, 303 insertions(+), 251 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 824b340377..91976cd190 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -319,7 +319,33 @@ class MenuItem_bool : public MenuEditItemBase { //////////////////////////////////////////// /** - * SCREEN_OR_MENU_LOOP generates init code for a screen or menu + * Marlin's native menu screens work by running a loop from the top visible line index + * to the bottom visible line index (according to how much the screen has been scrolled). + * This complete loop is done on every menu screen call. + * + * The menu system is highly dynamic, so it doesn't know ahead of any menu loop which + * items will be visible or hidden, so menu items don't have a fixed index number. + * + * During the loop, each menu item checks to see if its line is the current one. If it is, + * then it checks to see if a click has arrived so it can run its action. If the action + * doesn't redirect to another screen then the menu item calls its draw method. + * + * Menu item add-ons can do whatever they like. + * + * This mixture of drawing and processing inside a loop has the advantage that a single + * line can be used to represent a menu item, and that is the rationale for this design. + * + * One of the pitfalls of this method is that DOGM displays call the screen handler 2x, + * 4x, or 8x per screen update to draw just one segment of the screen. As a result, any + * menu item that exists in two screen segments is drawn and processed twice per screen + * update. With each item processed 5, 10, 20, or 40 times the logic has to be simple. + * + * To keep performance optimal, use the MENU_ITEM_IF/ELSE/ELIF macros. If function calls + * are needed to test conditions, they should come before START_MENU / START_SCREEN. + */ + +/** + * SCREEN_OR_MENU_LOOP generates header code for a screen or menu * * encoderTopLine is the top menu line to display * _lcdLineNr is the index of the LCD line (e.g., 0-3) @@ -510,6 +536,17 @@ class MenuItem_bool : public MenuEditItemBase { #define YESNO_ITEM_N_P(N,PLABEL, V...) _CONFIRM_ITEM_N_P(N, PLABEL, ##V) #define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_P(N, GET_TEXT(LABEL), ##V) +/** + * MENU_ITEM_IF/ELSE/ELIF + * + * Apply a condition for a menu item to exist. + * When the condition passes, NEXT_ITEM updates _thisItemNr. + * This cannot be used to wrap multiple menu items. + */ +#define MENU_ITEM_IF(COND) if ((_menuLineNr == _thisItemNr) && (COND)) +#define MENU_ITEM_ELIF(COND) else if ((_menuLineNr == _thisItemNr) && (COND)) +#define MENU_ITEM_ELSE else if (_menuLineNr == _thisItemNr) + //////////////////////////////////////////// /////////////// Menu Screens /////////////// //////////////////////////////////////////// diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index eac83c1d11..e055b5c8e8 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -45,7 +45,6 @@ #if ENABLED(FILAMENT_RUNOUT_SENSOR) && FILAMENT_RUNOUT_DISTANCE_MM #include "../../feature/runout.h" - float lcd_runout_distance_mm; #endif #if ENABLED(EEPROM_SETTINGS) && DISABLED(SLIM_LCD_MENUS) @@ -148,9 +147,12 @@ void menu_cancelobject(); #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) && FILAMENT_RUNOUT_DISTANCE_MM - EDIT_ITEM(float3, MSG_RUNOUT_DISTANCE_MM, &lcd_runout_distance_mm, 1, 30, []{ - runout.set_runout_distance(lcd_runout_distance_mm); - }); + MENU_ITEM_IF(1) { + editable.decimal = runout.runout_distance(); + EDIT_ITEM(float3, MSG_RUNOUT_DISTANCE_MM, &editable.decimal, 1, 30, + []{ runout.set_runout_distance(editable.decimal); }, true + ); + } #endif END_MENU(); @@ -327,9 +329,6 @@ void menu_cancelobject(); // M203 / M205 Velocity options void menu_advanced_velocity() { - START_MENU(); - BACK_ITEM(MSG_ADVANCED_SETTINGS); - // M203 Max Feedrate constexpr xyze_feedrate_t max_fr_edit = #ifdef MAX_FEEDRATE_EDIT_VALUES @@ -345,6 +344,10 @@ void menu_cancelobject(); #else const xyze_feedrate_t &max_fr_edit_scaled = max_fr_edit; #endif + + START_MENU(); + BACK_ITEM(MSG_ADVANCED_SETTINGS); + #define EDIT_VMAX(N) EDIT_ITEM_FAST(float3, MSG_VMAX_##N, &planner.settings.max_feedrate_mm_s[_AXIS(N)], 1, max_fr_edit_scaled[_AXIS(N)]) EDIT_VMAX(A); EDIT_VMAX(B); @@ -369,18 +372,7 @@ void menu_cancelobject(); // M201 / M204 Accelerations void menu_advanced_acceleration() { - START_MENU(); - BACK_ITEM(MSG_ADVANCED_SETTINGS); - const float max_accel = _MAX(planner.settings.max_acceleration_mm_per_s2[A_AXIS], planner.settings.max_acceleration_mm_per_s2[B_AXIS], planner.settings.max_acceleration_mm_per_s2[C_AXIS]); - // M204 P Acceleration - EDIT_ITEM_FAST(float5_25, MSG_ACC, &planner.settings.acceleration, 25, max_accel); - - // M204 R Retract Acceleration - EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); - - // M204 T Travel Acceleration - EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel); // M201 settings constexpr xyze_ulong_t max_accel_edit = @@ -398,6 +390,18 @@ void menu_cancelobject(); const xyze_ulong_t &max_accel_edit_scaled = max_accel_edit; #endif + START_MENU(); + BACK_ITEM(MSG_ADVANCED_SETTINGS); + + // M204 P Acceleration + EDIT_ITEM_FAST(float5_25, MSG_ACC, &planner.settings.acceleration, 25, max_accel); + + // M204 R Retract Acceleration + EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + + // M204 T Travel Acceleration + EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel); + #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST(long5_25, MSG_AMAX_##Q, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.reset_acceleration_rates(); }) EDIT_AMAX(A, 100); EDIT_AMAX(B, 100); @@ -413,8 +417,10 @@ void menu_cancelobject(); #ifdef XY_FREQUENCY_LIMIT EDIT_ITEM(int8, MSG_XY_FREQUENCY_LIMIT, &planner.xy_freq_limit_hz, 0, 100, planner.refresh_frequency_limit, true); - editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255 * 100)); // percent to u8 - EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); + MENU_ITEM_IF(1) { + editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255 * 100)); // percent to u8 + EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); + } #endif END_MENU(); @@ -496,9 +502,8 @@ void menu_advanced_steps_per_mm() { } void menu_advanced_settings() { - #if ENABLED(FILAMENT_RUNOUT_SENSOR) && FILAMENT_RUNOUT_DISTANCE_MM - lcd_runout_distance_mm = runout.runout_distance(); - #endif + const bool is_busy = printer_busy(); + START_MENU(); BACK_ITEM(MSG_CONFIGURATION); @@ -522,13 +527,13 @@ void menu_advanced_settings() { // M851 - Z Probe Offsets #if HAS_BED_PROBE - if (!printer_busy()) - SUBMENU(MSG_ZPROBE_OFFSETS, menu_probe_offsets); + if (!is_busy) SUBMENU(MSG_ZPROBE_OFFSETS, menu_probe_offsets); #endif + #endif // !SLIM_LCD_MENUS // M92 - Steps Per mm - if (!printer_busy()) + if (!is_busy) SUBMENU(MSG_STEPS_PER_MM, menu_advanced_steps_per_mm); #if ENABLED(BACKLASH_GCODE) @@ -571,17 +576,19 @@ void menu_advanced_settings() { #endif #if ENABLED(SD_FIRMWARE_UPDATE) - bool sd_update_state = settings.sd_update_status(); - EDIT_ITEM(bool, MSG_MEDIA_UPDATE, &sd_update_state, []{ - // - // Toggle the SD Firmware Update state in EEPROM - // - const bool new_state = !settings.sd_update_status(), - didset = settings.set_sd_update_status(new_state); - TERN_(HAS_BUZZER, ui.completion_feedback(didset)); - ui.return_to_status(); - if (new_state) LCD_MESSAGEPGM(MSG_RESET_PRINTER); else ui.reset_status(); - }); + MENU_ITEM_IF (1) { + bool sd_update_state = settings.sd_update_status(); + EDIT_ITEM(bool, MSG_MEDIA_UPDATE, &sd_update_state, []{ + // + // Toggle the SD Firmware Update state in EEPROM + // + const bool new_state = !settings.sd_update_status(), + didset = settings.set_sd_update_status(new_state); + ui.completion_feedback(didset); + ui.return_to_status(); + if (new_state) LCD_MESSAGEPGM(MSG_RESET_PRINTER); else ui.reset_status(); + }); + } #endif #if ENABLED(EEPROM_SETTINGS) && DISABLED(SLIM_LCD_MENUS) diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 92ab856f61..fb0087ad0e 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -79,19 +79,14 @@ static inline void _lcd_level_bed_corners_homing() { bed_corner = 0; ui.goto_screen([]{ MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE), - _lcd_goto_next_corner, - []{ - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); - ui.goto_previous_screen_no_defer(); - }, - GET_TEXT( - #if ENABLED(LEVEL_CENTER_TOO) - MSG_LEVEL_BED_NEXT_POINT - #else - MSG_NEXT_CORNER - #endif - ), (PGM_P)nullptr, PSTR("?") + GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE) + , _lcd_goto_next_corner + , []{ + TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + ui.goto_previous_screen_no_defer(); + } + , GET_TEXT(TERN(LEVEL_CENTER_TOO, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) + , (PGM_P)nullptr, PSTR("?") ); }); ui.set_selection(true); diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index fa7d099d15..2592f26649 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -224,11 +224,12 @@ * Save Settings (Req: EEPROM_SETTINGS) */ void menu_bed_leveling() { + const bool is_homed = all_axes_known(), + is_valid = leveling_is_valid(); + START_MENU(); BACK_ITEM(MSG_MOTION); - const bool is_homed = all_axes_known(); - // Auto Home if not using manual probing #if NONE(PROBE_MANUALLY, MESH_BED_LEVELING) if (!is_homed) GCODES_ITEM(MSG_AUTO_HOME, G28_STR); @@ -244,21 +245,22 @@ void menu_bed_leveling() { #endif #if ENABLED(MESH_EDIT_MENU) - if (leveling_is_valid()) - SUBMENU(MSG_EDIT_MESH, menu_edit_mesh); + if (is_valid) SUBMENU(MSG_EDIT_MESH, menu_edit_mesh); #endif // Homed and leveling is valid? Then leveling can be toggled. - if (is_homed && leveling_is_valid()) { + if (is_homed && is_valid) { bool show_state = planner.leveling_active; EDIT_ITEM(bool, MSG_BED_LEVELING, &show_state, _lcd_toggle_bed_leveling); } // Z Fade Height #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - // Shadow for editing the fade height - editable.decimal = planner.z_fade_height; - EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); + MENU_ITEM_IF (1) { + // Shadow for editing the fade height + editable.decimal = planner.z_fade_height; + EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); + } #endif // diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index c8153fc209..68fb1c9910 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -53,17 +53,19 @@ static void lcd_cancel_object_confirm() { } void menu_cancelobject() { + const int8_t ao = cancelable.active_object; + START_MENU(); BACK_ITEM(MSG_MAIN); // Draw cancelable items in a loop - int8_t a = cancelable.active_object; for (int8_t i = -1; i < cancelable.object_count; i++) { - if (i == a) continue; - int8_t j = i < 0 ? a : i; - if (!cancelable.is_canceled(j)) - SUBMENU_N(j, MSG_CANCEL_OBJECT_N, lcd_cancel_object_confirm); - if (i < 0) SKIP_ITEM(); + if (i == ao) continue; // Active is drawn on -1 index + const int8_t j = i < 0 ? ao : i; // Active or index item + MENU_ITEM_IF (!cancelable.is_canceled(j)) { // Not canceled already? + SUBMENU_N(j, MSG_CANCEL_OBJECT_N, lcd_cancel_object_confirm); // Offer the option. + if (i < 0) SKIP_ITEM(); // Extra line after active + } } END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 0c58b24681..7c71dd2a1b 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -126,6 +126,8 @@ void menu_advanced_settings(); #include "../../module/motion.h" // for active_extruder void menu_toolchange_migration() { + PGM_P const msg_migrate = GET_TEXT(MSG_TOOL_MIGRATION_SWAP); + START_MENU(); BACK_ITEM(MSG_CONFIGURATION); @@ -134,7 +136,6 @@ void menu_advanced_settings(); EDIT_ITEM(uint8, MSG_TOOL_MIGRATION_END, &migration.last, 0, EXTRUDERS - 1); // Migrate to a chosen extruder - PGM_P const msg_migrate = GET_TEXT(MSG_TOOL_MIGRATION_SWAP); LOOP_L_N(s, EXTRUDERS) { if (s != active_extruder) { ACTION_ITEM_N_P(s, msg_migrate, []{ @@ -182,11 +183,12 @@ void menu_advanced_settings(); #if ENABLED(DUAL_X_CARRIAGE) void menu_idex() { + const bool need_g28 = !(TEST(axis_known_position, Y_AXIS) && TEST(axis_known_position, Z_AXIS)); + START_MENU(); BACK_ITEM(MSG_CONFIGURATION); GCODES_ITEM(MSG_IDEX_MODE_AUTOPARK, PSTR("M605 S1\nG28 X\nG1 X100")); - const bool need_g28 = !(TEST(axis_known_position, Y_AXIS) && TEST(axis_known_position, Z_AXIS)); GCODES_ITEM(MSG_IDEX_MODE_DUPLICATE, need_g28 ? PSTR("M605 S1\nT0\nG28\nM605 S2 X200\nG28 X\nG1 X100") // If Y or Z is not homed, do a full G28 first : PSTR("M605 S1\nT0\nM605 S2 X200\nG28 X\nG1 X100") @@ -237,9 +239,10 @@ void menu_advanced_settings(); #endif #if ENABLED(TOUCH_MI_PROBE) + void menu_touchmi() { - START_MENU(); ui.defer_status_screen(); + START_MENU(); BACK_ITEM(MSG_CONFIGURATION); GCODES_ITEM(MSG_TOUCHMI_INIT, PSTR("M851 Z0\nG28\nG1 F200 Z0")); SUBMENU(MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); @@ -247,6 +250,7 @@ void menu_advanced_settings(); GCODES_ITEM(MSG_TOUCHMI_ZTEST, PSTR("G28\nG1 F200 Z0")); END_MENU(); } + #endif #if ENABLED(CONTROLLER_FAN_MENU) @@ -342,6 +346,8 @@ void menu_advanced_settings(); #endif void menu_configuration() { + const bool busy = printer_busy(); + START_MENU(); BACK_ITEM(MSG_MAIN); @@ -367,7 +373,6 @@ void menu_configuration() { SUBMENU(MSG_CONTROLLER_FAN, menu_controller_fan); #endif - const bool busy = printer_busy(); if (!busy) { #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) SUBMENU(MSG_DELTA_CALIBRATE, menu_delta_calibrate); @@ -435,8 +440,7 @@ void menu_configuration() { #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); - if (!busy) - ACTION_ITEM(MSG_LOAD_EEPROM, lcd_load_settings); + if (!busy) ACTION_ITEM(MSG_LOAD_EEPROM, lcd_load_settings); #endif if (!busy) diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index d6639206bb..633206ba87 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -118,6 +118,8 @@ void lcd_delta_settings() { } void menu_delta_calibrate() { + const bool all_homed = all_axes_homed(); + START_MENU(); BACK_ITEM(MSG_MAIN); @@ -133,7 +135,7 @@ void menu_delta_calibrate() { #if ENABLED(DELTA_CALIBRATION_MENU) SUBMENU(MSG_AUTO_HOME, _lcd_delta_calibrate_home); - if (all_axes_homed()) { + if (all_homed) { SUBMENU(MSG_DELTA_CALIBRATE_X, _goto_tower_x); SUBMENU(MSG_DELTA_CALIBRATE_Y, _goto_tower_y); SUBMENU(MSG_DELTA_CALIBRATE_Z, _goto_tower_z); diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index fd6760cbfa..ec45eb3772 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -95,26 +95,37 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { * */ #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - void menu_change_filament() { - START_MENU(); - BACK_ITEM(MSG_MAIN); + void menu_change_filament() { // Say "filament change" when no print is active editable.int8 = printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT; + #if E_STEPPERS > 1 && ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) + bool too_cold = false; + for (uint8_t s = 0; !too_cold && s < E_STEPPERS; s++) + too_cold = thermalManager.targetTooColdToExtrude(s); + #endif + + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + const bool is_busy = printer_busy(); + #endif + + START_MENU(); + BACK_ITEM(MSG_MAIN); + // Change filament #if E_STEPPERS == 1 PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE); - if (thermalManager.targetTooColdToExtrude(active_extruder)) + MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(active_extruder)) SUBMENU_P(msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); - else + MENU_ITEM_ELSE GCODES_ITEM_P(msg, PSTR("M600 B0")); #else PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE_E); LOOP_L_N(s, E_STEPPERS) { - if (thermalManager.targetTooColdToExtrude(s)) + MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); - else { + MENU_ITEM_ELSE { ACTION_ITEM_N_P(s, msg, []{ char cmd[13]; sprintf_P(cmd, PSTR("M600 B0 T%i"), int(MenuItemBase::itemIndex)); @@ -125,20 +136,20 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { #endif #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - if (!printer_busy()) { + if (!is_busy) { // Load filament #if E_STEPPERS == 1 PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD); - if (thermalManager.targetTooColdToExtrude(active_extruder)) + MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(active_extruder)) SUBMENU_P(msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, 0); }); - else + MENU_ITEM_ELSE GCODES_ITEM_P(msg_load, PSTR("M701")); #else PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD_E); LOOP_L_N(s, E_STEPPERS) { - if (thermalManager.targetTooColdToExtrude(s)) + MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); - else { + MENU_ITEM_ELSE { ACTION_ITEM_N_P(s, msg_load, []{ char cmd[12]; sprintf_P(cmd, PSTR("M701 T%i"), int(MenuItemBase::itemIndex)); @@ -151,30 +162,22 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { // Unload filament #if E_STEPPERS == 1 PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD); - if (thermalManager.targetTooColdToExtrude(active_extruder)) + MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(active_extruder)) SUBMENU_P(msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, 0); }); - else + MENU_ITEM_ELSE GCODES_ITEM_P(msg_unload, PSTR("M702")); #else #if ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) - { - bool too_cold = false; - LOOP_L_N(s, E_STEPPERS) { - if (thermalManager.targetTooColdToExtrude(s)) { - too_cold = true; break; - } - } - if (!too_cold) - GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, PSTR("M702")); - else + MENU_ITEM_IF (too_cold) SUBMENU(MSG_FILAMENTUNLOAD_ALL, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, -1); }); - } + MENU_ITEM_ELSE + GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, PSTR("M702")); #endif PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD_E); LOOP_L_N(s, E_STEPPERS) { - if (thermalManager.targetTooColdToExtrude(s)) + MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); - else { + MENU_ITEM_ELSE { ACTION_ITEM_N_P(s, msg_unload, []{ char cmd[12]; sprintf_P(cmd, PSTR("M702 T%i"), int(MenuItemBase::itemIndex)); @@ -194,12 +197,9 @@ static uint8_t hotend_status_extruder = 0; static PGM_P pause_header() { switch (pause_mode) { - case PAUSE_MODE_CHANGE_FILAMENT: - return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER); - case PAUSE_MODE_LOAD_FILAMENT: - return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_LOAD); - case PAUSE_MODE_UNLOAD_FILAMENT: - return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_UNLOAD); + case PAUSE_MODE_CHANGE_FILAMENT: return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER); + case PAUSE_MODE_LOAD_FILAMENT: return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_LOAD); + case PAUSE_MODE_UNLOAD_FILAMENT: return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_UNLOAD); default: break; } return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_PAUSE); @@ -227,11 +227,18 @@ void menu_pause_option() { STATIC_ITEM(MSG_FILAMENT_CHANGE_OPTION_HEADER); #endif ACTION_ITEM(MSG_FILAMENT_CHANGE_OPTION_PURGE, []{ pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; }); + #if HAS_FILAMENT_SENSOR - if (runout.filament_ran_out) + const bool still_out = runout.filament_ran_out; + MENU_ITEM_IF (still_out) EDIT_ITEM(bool, MSG_RUNOUT_SENSOR, &runout.enabled, runout.reset); + #else + constexpr bool still_out = false; #endif - ACTION_ITEM(MSG_FILAMENT_CHANGE_OPTION_RESUME, []{ pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; }); + + MENU_ITEM_IF (!still_out) + ACTION_ITEM(MSG_FILAMENT_CHANGE_OPTION_RESUME, []{ pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; }); + END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index f8df26bf08..78153a594b 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -34,8 +34,8 @@ #include "game/game.h" #endif -#define VALUE_ITEM(MSG, VALUE, STYL) do{ char buffer[21]; strcpy_P(buffer, PSTR(": ")); strcpy(buffer + 2, VALUE); STATIC_ITEM(MSG, STYL, buffer); }while(0) -#define VALUE_ITEM_P(MSG, PVALUE, STYL) do{ char buffer[21]; strcpy_P(buffer, PSTR(": ")); strcpy_P(buffer + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, buffer); }while(0) +#define VALUE_ITEM(MSG, VALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy(msg + 2, VALUE); STATIC_ITEM(MSG, STYL, msg); }while(0) +#define VALUE_ITEM_P(MSG, PVALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy_P(msg + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, msg); }while(0) #if ENABLED(PRINTCOUNTER) @@ -47,8 +47,6 @@ void menu_info_stats() { if (ui.use_click()) return ui.go_back(); - char buffer[21]; // For macro usage - printStatistics stats = print_job_timer.getStats(); char buffer[21]; @@ -245,17 +243,13 @@ void menu_info_board() { STATIC_ITEM_P(PSTR(MACHINE_NAME)); // My3DPrinter STATIC_ITEM_P(PSTR(WEBSITE_URL)); // www.my3dprinter.com VALUE_ITEM_P(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); // Extruders: 2 - #if ENABLED(AUTO_BED_LEVELING_3POINT) - STATIC_ITEM(MSG_3POINT_LEVELING); // 3-Point Leveling - #elif ENABLED(AUTO_BED_LEVELING_LINEAR) - STATIC_ITEM(MSG_LINEAR_LEVELING); // Linear Leveling - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - STATIC_ITEM(MSG_BILINEAR_LEVELING); // Bi-linear Leveling - #elif ENABLED(AUTO_BED_LEVELING_UBL) - STATIC_ITEM(MSG_UBL_LEVELING); // Unified Bed Leveling - #elif ENABLED(MESH_BED_LEVELING) - STATIC_ITEM(MSG_MESH_LEVELING); // Mesh Leveling - #endif + STATIC_ITEM( + TERN_(AUTO_BED_LEVELING_3POINT, MSG_3POINT_LEVELING) // 3-Point Leveling + TERN_(AUTO_BED_LEVELING_LINEAR, MSG_LINEAR_LEVELING) // Linear Leveling + TERN_(AUTO_BED_LEVELING_BILINEAR, MSG_BILINEAR_LEVELING) // Bi-linear Leveling + TERN_(AUTO_BED_LEVELING_UBL, MSG_UBL_LEVELING) // Unified Bed Leveling + TERN_(MESH_BED_LEVELING, MSG_MESH_LEVELING) // Mesh Leveling + ); END_SCREEN(); } @@ -282,27 +276,26 @@ void menu_info() { #endif #if HAS_GAMES + { #if ENABLED(GAMES_EASTER_EGG) - SKIP_ITEM(); - SKIP_ITEM(); - SKIP_ITEM(); + SKIP_ITEM(); SKIP_ITEM(); SKIP_ITEM(); #endif + // Game sub-menu or the individual game - { - SUBMENU( - #if HAS_GAME_MENU - MSG_GAMES, menu_game - #elif ENABLED(MARLIN_BRICKOUT) - MSG_BRICKOUT, brickout.enter_game - #elif ENABLED(MARLIN_INVADERS) - MSG_INVADERS, invaders.enter_game - #elif ENABLED(MARLIN_SNAKE) - MSG_SNAKE, snake.enter_game - #elif ENABLED(MARLIN_MAZE) - MSG_MAZE, maze.enter_game - #endif - ); - } + SUBMENU( + #if HAS_GAME_MENU + MSG_GAMES, menu_game + #elif ENABLED(MARLIN_BRICKOUT) + MSG_BRICKOUT, brickout.enter_game + #elif ENABLED(MARLIN_INVADERS) + MSG_INVADERS, invaders.enter_game + #elif ENABLED(MARLIN_SNAKE) + MSG_SNAKE, snake.enter_game + #elif ENABLED(MARLIN_MAZE) + MSG_MAZE, maze.enter_game + #endif + ); + } #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index ea76ae74dd..62689b8a4c 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -70,8 +70,10 @@ void menu_led_custom() { void menu_led() { START_MENU(); BACK_ITEM(MSG_MAIN); - bool led_on = leds.lights_on; - EDIT_ITEM(bool, MSG_LEDS, &led_on, leds.toggle); + MENU_ITEM_IF(1) { + bool led_on = leds.lights_on; + EDIT_ITEM(bool, MSG_LEDS, &led_on, leds.toggle); + } ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds.set_default); #if ENABLED(LED_COLOR_PRESETS) SUBMENU(MSG_LED_PRESETS, menu_led_presets); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index a834c28aab..7e7ea71cef 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -84,9 +84,6 @@ void menu_configuration(); extern const char M21_STR[]; void menu_main() { - START_MENU(); - BACK_ITEM(MSG_INFO_SCREEN); - const bool busy = printingIsActive() #if ENABLED(SDSUPPORT) , card_detected = card.isMounted() @@ -94,6 +91,9 @@ void menu_main() { #endif ; + START_MENU(); + BACK_ITEM(MSG_INFO_SCREEN); + if (busy) { #if MACHINE_CAN_PAUSE ACTION_ITEM(MSG_PAUSE_PRINT, ui.pause_print); @@ -119,7 +119,7 @@ void menu_main() { // Autostart // #if ENABLED(MENU_ADDAUTOSTART) - if (!busy) ACTION_ITEM(MSG_AUTOSTART, card.beginautostart); + ACTION_ITEM(MSG_AUTOSTART, card.beginautostart); #endif if (card_detected) { @@ -144,7 +144,7 @@ void menu_main() { #endif // !HAS_ENCODER_WHEEL && SDSUPPORT - if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) + MENU_ITEM_IF (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); SUBMENU(MSG_MOTION, menu_motion); @@ -176,9 +176,9 @@ void menu_main() { #if ENABLED(ADVANCED_PAUSE_FEATURE) #if E_STEPPERS == 1 && DISABLED(FILAMENT_LOAD_UNLOAD_GCODES) - if (thermalManager.targetHotEnoughToExtrude(active_extruder)) + MENU_ITEM_IF (thermalManager.targetHotEnoughToExtrude(active_extruder)) GCODES_ITEM(MSG_FILAMENTCHANGE, PSTR("M600 B0")); - else + MENU_ITEM_ELSE SUBMENU(MSG_FILAMENTCHANGE, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); #else SUBMENU(MSG_FILAMENTCHANGE, menu_change_filament); @@ -197,41 +197,44 @@ void menu_main() { // Switch power on/off // #if ENABLED(PSU_CONTROL) - if (powersupply_on) + MENU_ITEM_IF (powersupply_on) GCODES_ITEM(MSG_SWITCH_PS_OFF, PSTR("M81")); - else + MENU_ITEM_ELSE GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif #if BOTH(HAS_ENCODER_WHEEL, SDSUPPORT) - // *** IF THIS SECTION IS CHANGED, REPRODUCE ABOVE *** + if (!busy) { - // - // Autostart - // - #if ENABLED(MENU_ADDAUTOSTART) - if (!busy) ACTION_ITEM(MSG_AUTOSTART, card.beginautostart); - #endif + // *** IF THIS SECTION IS CHANGED, REPRODUCE ABOVE *** - if (card_detected) { - if (!card_open) { - MENU_ITEM(gcode, - #if PIN_EXISTS(SD_DETECT) - MSG_CHANGE_MEDIA, M21_STR - #else - MSG_RELEASE_MEDIA, PSTR("M22") - #endif - ); - SUBMENU(MSG_MEDIA_MENU, menu_media); - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, M21_STR); + // + // Autostart + // + #if ENABLED(MENU_ADDAUTOSTART) + ACTION_ITEM(MSG_AUTOSTART, card.beginautostart); #endif + + if (card_detected) { + if (!card_open) { + MENU_ITEM(gcode, + #if PIN_EXISTS(SD_DETECT) + MSG_CHANGE_MEDIA, M21_STR + #else + MSG_RELEASE_MEDIA, PSTR("M22") + #endif + ); + SUBMENU(MSG_MEDIA_MENU, menu_media); + } + } + else { + #if PIN_EXISTS(SD_DETECT) + ACTION_ITEM(MSG_NO_MEDIA, nullptr); + #else + GCODES_ITEM(MSG_ATTACH_MEDIA, M21_STR); + #endif + } } #endif // HAS_ENCODER_WHEEL && SDSUPPORT diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 3c7c9dff8e..3b3c78c1d7 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -45,25 +45,11 @@ void lcd_sd_updir() { void MarlinUI::reselect_last_file() { if (sd_encoder_position == 0xFFFF) return; - //#if HAS_GRAPHICAL_LCD - // // This is a hack to force a screen update. - // ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); - // ui.synchronize(); - // safe_delay(50); - // ui.synchronize(); - // ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); - // ui.drawing_screen = ui.screen_changed = true; - //#endif - goto_screen(menu_media, sd_encoder_position, sd_top_line, sd_items); sd_encoder_position = 0xFFFF; - defer_status_screen(); - - //#if HAS_GRAPHICAL_LCD - // update(); - //#endif } + #endif inline void sdcard_start_selected_file() { @@ -141,14 +127,13 @@ void menu_media() { if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { if (_menuLineNr == _thisItemNr) { card.getfilename_sorted(SD_ORDER(i, fileCnt)); - if (card.flag.filenameIsDir) + MENU_ITEM_IF (card.flag.filenameIsDir) MENU_ITEM(sdfolder, MSG_MEDIA_MENU, card); - else + MENU_ITEM_ELSE MENU_ITEM(sdfile, MSG_MEDIA_MENU, card); } - else { + else SKIP_ITEM(); - } } END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 9e069c92af..63533ee22c 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -193,6 +193,11 @@ void _goto_manual_move(const float scale) { void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=-1) { _manual_move_func_ptr = func; + #if ENABLED(PREVENT_COLD_EXTRUSION) + const bool too_cold = axis == E_AXIS && thermalManager.tooColdToExtrude(eindex >= 0 ? eindex : active_extruder); + #else + constexpr bool too_cold = false; + #endif START_MENU(); if (LCD_HEIGHT >= 4) { switch (axis) { @@ -205,24 +210,17 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int break; } } - #if ENABLED(PREVENT_COLD_EXTRUSION) - if (axis == E_AXIS && thermalManager.tooColdToExtrude(eindex >= 0 ? eindex : active_extruder)) - BACK_ITEM(MSG_HOTEND_TOO_COLD); - else - #endif - { + if (too_cold) + BACK_ITEM(MSG_HOTEND_TOO_COLD); + else { BACK_ITEM(MSG_MOVE_AXIS); SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); - if (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { + MENU_ITEM_IF (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { extern const char NUL_STR[]; SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); - MENU_ITEM_ADDON_START(0 - #if HAS_CHARACTER_LCD - + 1 - #endif - ); + MENU_ITEM_ADDON_START(0 + ENABLED(HAS_CHARACTER_LCD)); char tmp[20], numstr[10]; // Determine digits needed right of decimal const uint8_t digs = !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 1000 - int((SHORT_MANUAL_Z_MOVE) * 1000)) ? 4 : @@ -273,23 +271,23 @@ void menu_move() { } #elif EXTRUDERS == 3 if (active_extruder < 2) { - if (active_extruder) + MENU_ITEM_IF (active_extruder) GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); - else + MENU_ITEM_ELSE GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); } #else - if (active_extruder) + MENU_ITEM_IF (active_extruder) GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); - else + MENU_ITEM_ELSE GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); #endif #elif ENABLED(DUAL_X_CARRIAGE) - if (active_extruder) + MENU_ITEM_IF (active_extruder) GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); - else + MENU_ITEM_ELSE GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); #endif @@ -304,10 +302,8 @@ void menu_move() { #if EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) // ...and the non-switching - #if E_MANUAL == 5 - SUBMENU_MOVE_E(4); - #elif E_MANUAL == 3 - SUBMENU_MOVE_E(2); + #if E_MANUAL == 7 || E_MANUAL == 5 || E_MANUAL == 3 + SUBMENU_MOVE_E(E_MANUAL - 1); #endif #elif MULTI_MANUAL @@ -339,10 +335,8 @@ void menu_motion() { // // Move Axis // - #if ENABLED(DELTA) - if (all_axes_homed()) - #endif - SUBMENU(MSG_MOVE_AXIS, menu_move); + MENU_ITEM_IF (TERN1(DELTA, all_axes_homed())) + SUBMENU(MSG_MOVE_AXIS, menu_move); // // Auto Home @@ -370,20 +364,25 @@ void menu_motion() { #elif ENABLED(LCD_BED_LEVELING) - if (!g29_in_progress) SUBMENU(MSG_BED_LEVELING, menu_bed_leveling); + MENU_ITEM_IF (!g29_in_progress) + SUBMENU(MSG_BED_LEVELING, menu_bed_leveling); #elif HAS_LEVELING && DISABLED(SLIM_LCD_MENUS) #if DISABLED(PROBE_MANUALLY) GCODES_ITEM(MSG_LEVEL_BED, PSTR("G28\nG29")); #endif - if (all_axes_homed() && leveling_is_valid()) { + + MENU_ITEM_IF (all_axes_homed() && leveling_is_valid()) { bool show_state = planner.leveling_active; EDIT_ITEM(bool, MSG_BED_LEVELING, &show_state, _lcd_toggle_bed_leveling); } + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - editable.decimal = planner.z_fade_height; - EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); + MENU_ITEM_IF(1) { + editable.decimal = planner.z_fade_height; + EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); + } #endif #endif diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index d8e680ec3c..26cac93383 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -34,18 +34,19 @@ void menu_spindle_laser() { + const bool can_disable = cutter.enabled() && cutter.isOn; + START_MENU(); BACK_ITEM(MSG_MAIN); + #if ENABLED(SPINDLE_LASER_PWM) - EDIT_ITEM_FAST(CUTTER_MENU_POWER_TYPE, MSG_CUTTER(POWER), &cutter.setPower, cutter.interpret_power(SPEED_POWER_MIN), cutter.interpret_power(SPEED_POWER_MAX), - []{ - if (cutter.isOn) { - cutter.power = cutter.setPower; - } - }); + EDIT_ITEM_FAST( CUTTER_MENU_POWER_TYPE, MSG_CUTTER(POWER), &cutter.setPower + , cutter.interpret_power(SPEED_POWER_MIN), cutter.interpret_power(SPEED_POWER_MAX) + , []{ if (cutter.isOn) cutter.power = cutter.setPower; } + ); #endif - if (cutter.enabled() && cutter.isOn) + if (can_disable) ACTION_ITEM(MSG_CUTTER(OFF), cutter.disable); else { ACTION_ITEM(MSG_CUTTER(ON), cutter.enable_forward); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 397a320a8b..9be20b52e2 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -197,8 +197,10 @@ void menu_temperature() { #if HAS_FAN1 || HAS_FAN2 || HAS_FAN3 || HAS_FAN4 || HAS_FAN5 || HAS_FAN6 || HAS_FAN7 auto fan_edit_items = [&](const uint8_t f) { - editable.uint8 = thermalManager.fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); + MENU_ITEM_IF(1) { + editable.uint8 = thermalManager.fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); + } #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, f, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[f], 3, 255); #endif @@ -208,14 +210,18 @@ void menu_temperature() { #define SNFAN(N) (ENABLED(SINGLENOZZLE) && !HAS_FAN##N && EXTRUDERS > N) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) auto singlenozzle_item = [&](const uint8_t f) { - editable.uint8 = thermalManager.fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); + MENU_ITEM_IF(1) { + editable.uint8 = thermalManager.fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); + } }; #endif #if HAS_FAN0 - editable.uint8 = thermalManager.fan_speed[0]; - EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); + MENU_ITEM_IF(1) { + editable.uint8 = thermalManager.fan_speed[0]; + EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); + } #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255); #endif @@ -274,10 +280,12 @@ void menu_temperature() { // // Cooldown // - bool has_heat = false; - HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } - if (TERN0(HAS_HEATED_BED, thermalManager.temp_bed.target)) has_heat = true; - if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); + MENU_ITEM_IF(1) { + bool has_heat = false; + HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } + if (TERN0(HAS_HEATED_BED, thermalManager.temp_bed.target)) has_heat = true; + if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); + } #endif // HAS_TEMP_HOTEND diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 03d9302c64..cc5b6e4770 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -146,8 +146,10 @@ void menu_tune() { #if HAS_FAN1 || HAS_FAN2 || HAS_FAN3 || HAS_FAN4 || HAS_FAN5 || HAS_FAN6 || HAS_FAN7 auto fan_edit_items = [&](const uint8_t f) { - editable.uint8 = thermalManager.fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); + MENU_ITEM_IF(1) { + editable.uint8 = thermalManager.fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); + } #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, f, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[f], 3, 255); #endif @@ -157,14 +159,18 @@ void menu_tune() { #define SNFAN(N) (ENABLED(SINGLENOZZLE) && !HAS_FAN##N && EXTRUDERS > N) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) auto singlenozzle_item = [&](const uint8_t f) { - editable.uint8 = thermalManager.fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); + MENU_ITEM_IF(1) { + editable.uint8 = thermalManager.fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); + } }; #endif #if HAS_FAN0 - editable.uint8 = thermalManager.fan_speed[0]; - EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); + MENU_ITEM_IF(1) { + editable.uint8 = thermalManager.fan_speed[0]; + EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); + } #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 683470c782..fdb0da0b3c 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -376,9 +376,8 @@ void _lcd_ubl_storage_mesh() { int16_t a = settings.calc_num_meshes(); START_MENU(); BACK_ITEM(MSG_UBL_LEVEL_BED); - if (!WITHIN(ubl_storage_slot, 0, a - 1)) { + if (!WITHIN(ubl_storage_slot, 0, a - 1)) STATIC_ITEM(MSG_UBL_NO_STORAGE); - } else { EDIT_ITEM(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, a - 1); ACTION_ITEM(MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); @@ -580,9 +579,9 @@ void _lcd_ubl_step_by_step() { void _lcd_ubl_level_bed() { START_MENU(); BACK_ITEM(MSG_MOTION); - if (planner.leveling_active) + MENU_ITEM_IF (planner.leveling_active) GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); - else + MENU_ITEM_ELSE GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); SUBMENU(MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step); ACTION_ITEM(MSG_UBL_MESH_EDIT, _lcd_ubl_output_map_lcd_cmd); From 89b17b54637200838e52ae39a9e4b23f3c2f8d35 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Tue, 28 Apr 2020 07:21:23 +0200 Subject: [PATCH 0317/1454] Followup fixes for singlenozzle, etc. (#17712) --- Marlin/Configuration.h | 7 ++++ Marlin/Configuration_adv.h | 2 +- Marlin/src/gcode/temp/M104_M109.cpp | 4 +-- Marlin/src/lcd/menu/menu_temperature.cpp | 9 +++--- Marlin/src/lcd/menu/menu_tune.cpp | 9 +++--- Marlin/src/module/planner.cpp | 11 +++++++ Marlin/src/module/planner.h | 1 + Marlin/src/module/temperature.cpp | 2 +- Marlin/src/module/tool_change.cpp | 41 +++++++++++++----------- Marlin/src/module/tool_change.h | 9 +++--- 10 files changed, 61 insertions(+), 34 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index a69cecf4a0..38c4ae4c94 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -150,6 +150,13 @@ // For Cyclops or any "multi-extruder" that shares a single nozzle. //#define SINGLENOZZLE +// Save and restore temperature and fan speed on tool-change. +// Set standby for the unselected tool with M104/106/109 T... +#if ENABLED(SINGLENOZZLE) + //#define SINGLENOZZLE_STANDBY_TEMP + //#define SINGLENOZZLE_STANDBY_FAN +#endif + /** * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. * diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fb82aed698..86a240e7db 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1889,7 +1889,7 @@ // (May break filament if not retracted beforehand.) //#define TOOLCHANGE_FS_INIT_BEFORE_SWAP - // Prime on the first T command even if the same or no toolchange / swap + // Prime on the first T0 (If other, TOOLCHANGE_FS_INIT_BEFORE_SWAP applied) // Enable it (M217 V[0/1]) before printing, to avoid unwanted priming on host connect //#define TOOLCHANGE_FS_PRIME_FIRST_USED diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index eec97df9e6..bb453412d7 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -65,7 +65,7 @@ void GcodeSuite::M104() { if (parser.seenval('S')) { const int16_t temp = parser.value_celsius(); - #if ENABLED(SINGLENOZZLE) + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) singlenozzle_temp[target_extruder] = temp; if (target_extruder != active_extruder) return; #endif @@ -111,7 +111,7 @@ void GcodeSuite::M109() { set_temp = no_wait_for_cooling || parser.seenval('R'); if (set_temp) { const int16_t temp = parser.value_celsius(); - #if ENABLED(SINGLENOZZLE) + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) singlenozzle_temp[target_extruder] = temp; if (target_extruder != active_extruder) return; #endif diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 9be20b52e2..5526848939 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -168,8 +168,9 @@ void menu_temperature() { EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif - #if ENABLED(SINGLENOZZLE) - EDIT_ITEM_FAST(uint16_3, MSG_NOZZLE_STANDBY, &singlenozzle_temp[active_extruder ? 0 : 1], 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + LOOP_S_L_N(e, 1, EXTRUDERS) + EDIT_ITEM_FAST_N(uint16_3, e, MSG_NOZZLE_STANDBY, &singlenozzle_temp[e], 0, thermalManager.heater_maxtemp[0] - HOTEND_OVERSHOOT); #endif // @@ -207,11 +208,11 @@ void menu_temperature() { }; #endif - #define SNFAN(N) (ENABLED(SINGLENOZZLE) && !HAS_FAN##N && EXTRUDERS > N) + #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && EXTRUDERS > N) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) auto singlenozzle_item = [&](const uint8_t f) { MENU_ITEM_IF(1) { - editable.uint8 = thermalManager.fan_speed[f]; + editable.uint8 = singlenozzle_fan_speed[f]; EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); } }; diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index cc5b6e4770..e510bae634 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -124,8 +124,9 @@ void menu_tune() { EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.heater_maxtemp[e] - HOTEND_OVERSHOOT, []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); #endif - #if ENABLED(SINGLENOZZLE) - EDIT_ITEM_FAST(uint16_3, MSG_NOZZLE_STANDBY, &singlenozzle_temp[active_extruder ? 0 : 1], 0, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + LOOP_S_L_N(e, 1, EXTRUDERS) + EDIT_ITEM_FAST_N(uint16_3, e, MSG_NOZZLE_STANDBY, &singlenozzle_temp[e], 0, thermalManager.heater_maxtemp[0] - HOTEND_OVERSHOOT); #endif // @@ -156,11 +157,11 @@ void menu_tune() { }; #endif - #define SNFAN(N) (ENABLED(SINGLENOZZLE) && !HAS_FAN##N && EXTRUDERS > N) + #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && EXTRUDERS > N) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) auto singlenozzle_item = [&](const uint8_t f) { MENU_ITEM_IF(1) { - editable.uint8 = thermalManager.fan_speed[f]; + editable.uint8 = singlenozzle_fan_speed[f]; EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); } }; diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index ad9dffe4ea..4e675f075d 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2861,6 +2861,17 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { #if ENABLED(AUTOTEMP) +void Planner::autotemp_update() { + + #if ENABLED(AUTOTEMP_PROPORTIONAL) + const int16_t target = thermalManager.degTargetHotend(active_extruder); + autotemp_min = target + AUTOTEMP_MIN_P; + autotemp_max = target + AUTOTEMP_MAX_P; + #endif + autotemp_factor = TERN(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P, 0); + autotemp_enabled = autotemp_factor != 0; +} + void Planner::autotemp_M104_M109() { #if ENABLED(AUTOTEMP_PROPORTIONAL) diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ebfb8dcb9e..7b029cba01 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -824,6 +824,7 @@ class Planner { static bool autotemp_enabled; static void getHighESpeed(); static void autotemp_M104_M109(); + static void autotemp_update(); #endif #if HAS_LINEAR_E_JERK diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e55dcb074b..78f8a19cf6 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -193,7 +193,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, NOMORE(speed, 255U); - #if ENABLED(SINGLENOZZLE) + #if ENABLED(SINGLENOZZLE_STANDBY_FAN) if (target != active_extruder) { if (target < EXTRUDERS) singlenozzle_fan_speed[target] = speed; return; diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 9908d37cda..c0f7909a3c 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -47,11 +47,12 @@ bool toolchange_extruder_ready[EXTRUDERS]; #endif -#if ENABLED(SINGLENOZZLE) +#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) uint16_t singlenozzle_temp[EXTRUDERS]; - #if HAS_FAN - uint8_t singlenozzle_fan_speed[EXTRUDERS]; - #endif +#endif + +#if BOTH(HAS_FAN, SINGLENOZZLE_STANDBY_FAN) + uint8_t singlenozzle_fan_speed[EXTRUDERS]; #endif #if ENABLED(MAGNETIC_PARKING_EXTRUDER) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) @@ -822,7 +823,7 @@ void tool_change_prime() { #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; - safe_delay(toolchange_settings.fan_time * 1000); + gcode.dwell(toolchange_settings.fan_time * 1000); thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = fansp; #endif @@ -934,7 +935,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Z raise before retraction #if ENABLED(TOOLCHANGE_ZRAISE_BEFORE_RETRACT) && DISABLED(SWITCHING_NOZZLE) - if (can_move_away && TERN1(toolchange_settings.enable_park)) { + if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; #if HAS_SOFTWARE_ENDSTOPS @@ -956,8 +957,12 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); if (ENABLED(SINGLENOZZLE)) { active_extruder = new_tool; return; } } - else - unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); + else { + // If first new tool, toolchange without unloading the old not initialized 'Just prime/init the new' + if (first_tool_is_primed) + unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); + first_tool_is_primed = true; // The first new tool will be primed by toolchanging + } } #endif @@ -1059,15 +1064,16 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { const bool should_move = safe_to_move && !no_move && IsRunning(); if (should_move) { - #if ENABLED(SINGLENOZZLE) - #if HAS_FAN - singlenozzle_fan_speed[old_tool] = thermalManager.fan_speed[0]; - thermalManager.fan_speed[0] = singlenozzle_fan_speed[new_tool]; - #endif + #if BOTH(HAS_FAN, SINGLENOZZLE_STANDBY_FAN) + singlenozzle_fan_speed[old_tool] = thermalManager.fan_speed[0]; + thermalManager.fan_speed[0] = singlenozzle_fan_speed[new_tool]; + #endif + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) singlenozzle_temp[old_tool] = thermalManager.temp_hotend[0].target; if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { thermalManager.setTargetHotend(singlenozzle_temp[new_tool], 0); + TERN_(AUTOTEMP, planner.autotemp_update()); TERN_(HAS_DISPLAY, thermalManager.set_heating_message(0)); (void)thermalManager.wait_for_hotend(0, false); // Wait for heating or cooling } @@ -1101,7 +1107,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; - safe_delay(toolchange_settings.fan_time * 1000); + gcode.dwell(toolchange_settings.fan_time * 1000); thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = fansp; #endif } @@ -1245,10 +1251,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Migrate the temperature to the new hotend #if HAS_MULTI_HOTEND - thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); - #if HAS_DISPLAY - thermalManager.set_heating_message(0); - #endif + thermalManager.setTargetHotend(thermalManager.temp_hotend[active_extruder].target, migration_extruder); + TERN_(AUTOTEMP, planner.autotemp_update()); + TERN_(HAS_DISPLAY, thermalManager.set_heating_message(0)); thermalManager.wait_for_hotend(active_extruder); #endif diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 7e73bd7bb2..4b004950ab 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -108,11 +108,12 @@ #endif -#if ENABLED(SINGLENOZZLE) +#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) extern uint16_t singlenozzle_temp[EXTRUDERS]; - #if HAS_FAN - extern uint8_t singlenozzle_fan_speed[EXTRUDERS]; - #endif +#endif + +#if BOTH(HAS_FAN, SINGLENOZZLE_STANDBY_FAN) + extern uint8_t singlenozzle_fan_speed[EXTRUDERS]; #endif TERN_(ELECTROMAGNETIC_SWITCHING_TOOLHEAD, void est_init()); From 0eeb5e2a29f2f76f0e5eeff661d3161c2910736b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Apr 2020 12:31:21 -0500 Subject: [PATCH 0318/1454] General cleanup: pause, MarlinCore --- Marlin/src/MarlinCore.cpp | 4 +--- Marlin/src/feature/pause.cpp | 33 ++++++++++----------------------- 2 files changed, 11 insertions(+), 26 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 6dc76947e5..28a1b0c98f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -214,9 +214,7 @@ bool wait_for_heatup = true; bool wait_for_user; // = false; void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { - #if DISABLED(ADVANCED_PAUSE_FEATURE) - UNUSED(no_sleep); - #endif + TERN(ADVANCED_PAUSE_FEATURE,,UNUSED(no_sleep)); KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; if (ms) ms += millis(); // expire time diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 396819324c..f3c57bc923 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -102,6 +102,8 @@ fil_change_settings_t fc_settings[EXTRUDERS]; } } } +#else + inline void filament_change_beep(const int8_t, const bool=false) {} #endif /** @@ -148,9 +150,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ DXC_ARGS ) { - #if !HAS_LCD_MENU - UNUSED(show_lcd); - #endif + TERN(HAS_LCD_MENU,,UNUSED(show_lcd)); if (!ensure_safe_temperature(mode)) { #if HAS_LCD_MENU @@ -165,11 +165,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_INSERT)); - #if HAS_BUZZER - filament_change_beep(max_beep_count, true); - #else - UNUSED(max_beep_count); - #endif + filament_change_beep(max_beep_count, true); KEEPALIVE_STATE(PAUSED_FOR_USER); #if ENABLED(HOST_PROMPT_SUPPORT) @@ -184,7 +180,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); while (wait_for_user) { - TERN_(HAS_BUZZER, filament_change_beep(max_beep_count)); + filament_change_beep(max_beep_count); idle_no_sleep(); } } @@ -285,9 +281,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, , const float &mix_multiplier/*=1.0*/ #endif ) { - #if !HAS_LCD_MENU - UNUSED(show_lcd); - #endif + TERN(HAS_LCD_MENU,,UNUSED(show_lcd)); #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) constexpr float mix_multiplier = 1.0; @@ -353,10 +347,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, uint8_t did_pause_print = 0; bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { - - #if !HAS_LCD_MENU - UNUSED(show_lcd); - #endif + TERN(HAS_LCD_MENU,,UNUSED(show_lcd)); if (did_pause_print) return false; // already paused @@ -457,11 +448,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep show_continue_prompt(is_reload); - #if HAS_BUZZER - filament_change_beep(max_beep_count, true); - #else - UNUSED(max_beep_count); - #endif + filament_change_beep(max_beep_count, true); // Start the heater idle timers const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); @@ -481,7 +468,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED))); wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { - TERN_(HAS_BUZZER, filament_change_beep(max_beep_count)); + filament_change_beep(max_beep_count); // If the nozzle has timed out... if (!nozzle_timed_out) @@ -521,7 +508,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep wait_for_user = true; nozzle_timed_out = false; - TERN_(HAS_BUZZER, filament_change_beep(max_beep_count, true)); + filament_change_beep(max_beep_count, true); } idle_no_sleep(); } From 07a6bf9b8464346326e9b35bcfa88a20fa2191d1 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 27 Apr 2020 23:31:05 -0600 Subject: [PATCH 0319/1454] Enhance and fix FTDI EVE Touch UI (#17755) - Stop print and play error sound if USB drive is removed. - Allow configuration of version string in touch UI. - Print a completion message in the bed mesh leveling screen. - Don't play redundant sound at the start of a print. - Clicking on percentage in status screen now goes into print speed screen - Clicking on axis in status screen now goes to nozzle motion screens - Use default increment of 100 when nozzle is preheated in temp screen, 10 otherwise - Fixed grayed out change filament button in tune menu - Eliminated code duplication in tune menu - Add button for resetting BLTouch to advanced settings menu --- .../ftdi_eve_touch_ui/language/language_en.h | 2 + .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 15 ++- .../screens/about_screen.cpp | 10 +- .../screens/advanced_settings_menu.cpp | 79 ++++---------- .../screens/bed_mesh_screen.cpp | 23 ++-- .../confirm_start_print_dialog_box.cpp | 5 - .../lib/ftdi_eve_touch_ui/screens/screens.h | 1 - .../screens/status_screen.cpp | 13 ++- .../screens/temperature_screen.cpp | 2 +- .../ftdi_eve_touch_ui/screens/tune_menu.cpp | 102 +++++------------- 10 files changed, 97 insertions(+), 155 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h index ebd60aed31..f521a4010a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h @@ -147,6 +147,8 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; + PROGMEM Language_Str MSG_BED_MAPPING_DONE = u8"Bed mapping finished"; + PROGMEM Language_Str MSG_RESET_BLTOUCH = u8"Reset BLTouch"; #ifdef TOUCH_UI_LULZBOT_BIO PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index 9271f2a0cd..e4dbf7b360 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -51,12 +51,17 @@ namespace ExtUI { } void onMediaRemoved() { - if (AT_SCREEN(StatusScreen)) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); - sound.play(media_removed, PLAY_ASYNCHRONOUS); - if (AT_SCREEN(FilesScreen)) { - GOTO_SCREEN(StatusScreen) + if (isPrintingFromMedia()) { + stopPrint(); + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); } + else + sound.play(media_removed, PLAY_ASYNCHRONOUS); + + if (AT_SCREEN(StatusScreen) || isPrintingFromMedia()) + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); + + if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen) } void onMediaError() { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp index 48b65608f2..93aff7ca5f 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp @@ -80,9 +80,15 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif , OPT_CENTER, font_xlarge ); - draw_text_box(cmd, FW_VERS_POS, progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); + draw_text_box(cmd, FW_VERS_POS, + #ifdef TOUCH_UI_VERSION + F(TOUCH_UI_VERSION) + #else + progmem_str(getFirmwareName_str()) + #endif + , OPT_CENTER, font_medium); draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); - draw_text_box(cmd.tag(3), INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); cmd.font(font_medium) .colors(normal_btn) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 2150c439e3..bf01ffac27 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -89,41 +89,18 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - .enabled( - #if HAS_BED_PROBE - 1 - #endif - ) + .enabled(ENABLED(HAS_BED_PROBE)) .tag(2) .button( ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - .enabled( - #if HAS_CASE_LIGHT - 1 - #endif - ) + .enabled(ENABLED(HAS_CASE_LIGHT)) .tag(16).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) .tag(3) .button( STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) + .enabled(ENABLED(HAS_TRINAMIC_CONFIG)) .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) - .enabled( - #if ENABLED(SENSORLESS_HOMING) - 1 - #endif - ) + .enabled(ENABLED(SENSORLESS_HOMING)) .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) - .enabled( - #if HAS_MULTI_HOTEND - 1 - #endif - ) - .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) - .enabled( - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - 1 - #endif + .enabled(EITHER(HAS_MULTI_HOTEND, BLTOUCH)) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_OFFSETS_MENU, MSG_RESET_BLTOUCH)) + .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) ) .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) @@ -132,18 +109,8 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) - .tag(7) .button( JERK_POS, GET_TEXT_F( - #if HAS_JUNCTION_DEVIATION - MSG_JUNCTION_DEVIATION - #else - MSG_JERK - #endif - )) - .enabled( - #if ENABLED(BACKLASH_GCODE) - 1 - #endif - ) + .tag(7) .button( JERK_POS, GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK)) + .enabled(ENABLED(BACKLASH_GCODE)) .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) .colors(action_btn) .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); @@ -152,27 +119,25 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; #if HAS_BED_PROBE - case 2: GOTO_SCREEN(ZOffsetScreen); break; + case 2: GOTO_SCREEN(ZOffsetScreen); break; #endif - case 3: GOTO_SCREEN(StepsScreen); break; - #if HAS_MULTI_HOTEND - case 4: GOTO_SCREEN(NozzleOffsetScreen); break; - #endif - case 5: GOTO_SCREEN(MaxVelocityScreen); break; - case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; - case 7: - #if HAS_JUNCTION_DEVIATION - GOTO_SCREEN(JunctionDeviationScreen); - #else - GOTO_SCREEN(JerkScreen); + case 3: GOTO_SCREEN(StepsScreen); break; + case 4: + #if HAS_MULTI_HOTEND + GOTO_SCREEN(NozzleOffsetScreen); + #elif ENABLED(BLTOUCH) + injectCommands_P(PSTR("M280 P0 S60")); #endif break; + case 5: GOTO_SCREEN(MaxVelocityScreen); break; + case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; + case 7: GOTO_SCREEN(TERN(HAS_JUNCTION_DEVIATION, JunctionDeviationScreen, JerkScreen)); break; #if ENABLED(BACKLASH_GCODE) - case 8: GOTO_SCREEN(BacklashCompensationScreen); break; + case 8: GOTO_SCREEN(BacklashCompensationScreen); break; #endif - case 9: GOTO_SCREEN(InterfaceSettingsScreen); LockScreen::check_passcode(); break; + case 9: GOTO_SCREEN(InterfaceSettingsScreen); LockScreen::check_passcode(); break; case 10: GOTO_SCREEN(RestoreFailsafeDialogBox); LockScreen::check_passcode(); break; #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) case 11: GOTO_SCREEN(FilamentMenu); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp index 2f015e594e..6ba7deea97 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -35,19 +35,19 @@ using namespace ExtUI; #define GRID_ROWS 10 #define MESH_POS BTN_POS(1, 2), BTN_SIZE(2,5) + #define MESSAGE_POS BTN_POS(1, 7), BTN_SIZE(2,1) #define Z_LABEL_POS BTN_POS(1, 8), BTN_SIZE(1,1) #define Z_VALUE_POS BTN_POS(2, 8), BTN_SIZE(1,1) - #define WAIT_POS BTN_POS(1, 8), BTN_SIZE(2,1) - #define BACK_POS BTN_POS(1,10), BTN_SIZE(2,1) + #define OKAY_POS BTN_POS(1,10), BTN_SIZE(2,1) #else #define GRID_COLS 5 #define GRID_ROWS 5 - #define MESH_POS BTN_POS(1,1), BTN_SIZE(3,5) - #define Z_LABEL_POS BTN_POS(4,2), BTN_SIZE(2,1) - #define Z_VALUE_POS BTN_POS(4,3), BTN_SIZE(2,1) - #define WAIT_POS BTN_POS(4,2), BTN_SIZE(2,2) - #define BACK_POS BTN_POS(4,5), BTN_SIZE(2,1) + #define MESH_POS BTN_POS(1,1), BTN_SIZE(3,5) + #define MESSAGE_POS BTN_POS(4,1), BTN_SIZE(2,1) + #define Z_LABEL_POS BTN_POS(4,2), BTN_SIZE(2,1) + #define Z_VALUE_POS BTN_POS(4,3), BTN_SIZE(2,1) + #define OKAY_POS BTN_POS(4,5), BTN_SIZE(2,1) #endif void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max) { @@ -238,7 +238,7 @@ void BedMeshScreen::drawHighlightedPointValue() { .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) .text(Z_VALUE_POS, str) .colors(action_btn) - .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)) + .tag(1).button( OKAY_POS, GET_TEXT_F(MSG_BUTTON_OKAY)) .tag(0); } @@ -261,7 +261,12 @@ void BedMeshScreen::onRedraw(draw_mode_t what) { constexpr float autoscale_max_amplitude = 0.03; const bool levelingFinished = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); - if (levelingFinished) drawHighlightedPointValue(); + if (levelingFinished) { + drawHighlightedPointValue(); + CommandProcessor cmd; + cmd.font(Theme::font_medium) + .text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); + } BedMeshScreen::drawMesh(INSET_POS(MESH_POS), ExtUI::getMeshArray(), USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0), diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp index 5c691cb9a1..63ce83765e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp @@ -31,11 +31,6 @@ using namespace FTDI; using namespace Theme; using namespace ExtUI; -void ConfirmStartPrintDialogBox::onEntry() { - BaseScreen::onEntry(); - sound.play(twinkle, PLAY_ASYNCHRONOUS); -} - void ConfirmStartPrintDialogBox::onRedraw(draw_mode_t) { const char *filename = getLongFilename(); char buffer[strlen_P(GET_TEXT(MSG_START_PRINT_CONFIRMATION)) + strlen(filename) + 1]; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 87522870b9..b2d5e55a12 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -223,7 +223,6 @@ class ConfirmStartPrintDialogBox : public DialogBoxBaseClass, public UncachedScr static const char *getFilename(bool longName); public: - static void onEntry(); static void onRedraw(draw_mode_t); static bool onTouchEnd(uint8_t); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp index 816f6986f5..d806c88ef5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp @@ -246,7 +246,7 @@ void StatusScreen::draw_progress(draw_mode_t what) { sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() ); cmd.font(font_medium) - .tag(0).text(TIME_POS, time_str) + .tag(7).text(TIME_POS, time_str) .text(PROGRESS_POS, progress_str); } } @@ -386,10 +386,19 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { break; case 5: GOTO_SCREEN(TemperatureScreen); break; case 6: - if (!isPrinting()) { + if (isPrinting()) { + #if ENABLED(BABYSTEPPING) + GOTO_SCREEN(NudgeNozzleScreen); + #elif HAS_BED_PROBE + GOTO_SCREEN(ZOffsetScreen); + #else + return false; + #endif + } else { GOTO_SCREEN(MoveAxisScreen); } break; + case 7: GOTO_SCREEN(FeedratePercentScreen); break; default: return true; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp index 5f8a74b0b0..d2b2c22ed3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp @@ -35,7 +35,7 @@ void TemperatureScreen::onRedraw(draw_mode_t what) { #if TOUCH_UI_LCD_TEMP_SCALING == 10 w.precision(1) #else - w.precision(0) + w.precision(0, getTargetTemp_celsius(E0) == 0 ? DEFAULT_HIGHEST : DEFAULT_MIDRANGE) #endif .color(temp).units(GET_TEXT_F(MSG_UNITS_C)); w.heading(GET_TEXT_F(MSG_TEMPERATURE)); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp index 8b4f0942fb..e85dc6f0fd 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp @@ -39,9 +39,25 @@ void TuneMenu::onRedraw(draw_mode_t what) { #ifdef TOUCH_UI_PORTRAIT #define GRID_ROWS 8 #define GRID_COLS 2 + #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define NUDGE_NOZ_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define SPEED_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define PAUSE_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define STOP_POS BTN_POS(1,7), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) #else #define GRID_ROWS 4 #define GRID_COLS 2 + #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define NUDGE_NOZ_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define SPEED_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define PAUSE_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define STOP_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #defome BACK_POS BTN_POS(2,4), BTN_SIZE(1,1) #endif if (what & FOREGROUND) { @@ -50,81 +66,21 @@ void TuneMenu::onRedraw(draw_mode_t what) { CommandProcessor cmd; cmd.colors(normal_btn) .font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .tag(2).enabled(1) .button( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_TEMPERATURE)) - .tag(3).enabled(!isPrinting()).button( BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - .enabled( - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - 1 - #endif - ) - .tag(9).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENT)) - #if ENABLED(BABYSTEPPING) - .tag(4).enabled(1) .button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_NUDGE_NOZZLE)) - #else - .enabled( - #if HAS_BED_PROBE - 1 - #endif - ) - .tag(4) .button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - #endif - .tag(5).enabled(1) .button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_SPEED)) + .tag(2).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) + .enabled(!isPrinting() || isPrintingFromMediaPaused()) + .tag(3).button( FIL_CHANGE_POS, GET_TEXT_F(MSG_FILAMENTCHANGE)) + .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) + .tag(9).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) + .enabled(EITHER(HAS_BED_PROBE, BABYSTEPPING)) + .tag(4).button( NUDGE_NOZ_POS, GET_TEXT_F(TERN(BABYSTEPPING, MSG_NUDGE_NOZZLE, MSG_ZPROBE_ZOFFSET)) + .tag(5).button( SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) .tag(isPrintingFromMediaPaused() ? 7 : 6) - .enabled( - #if ENABLED(SDSUPPORT) - isPrintingFromMedia() - #endif - ) - .button( BTN_POS(1,6), BTN_SIZE(2,1), isPrintingFromMediaPaused() ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) - .enabled( - #if ENABLED(SDSUPPORT) - isPrintingFromMedia() - #endif - ) - .tag(8) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_STOP_PRINT)) + .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) + .button( PAUSE_POS, isPrintingFromMediaPaused() ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) + .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) + .tag(8).button( STOP_POS, GET_TEXT_F(MSG_STOP_PRINT)) .tag(1).colors(action_btn) - .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #else // TOUCH_UI_PORTRAIT - .tag(2).enabled(1) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_TEMPERATURE)) - .tag(3).enabled(!isPrinting()).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - .enabled( - #if ENABLED(BABYSTEPPING) - isPrintingFromMedia() - #endif - ) - #if ENABLED(BABYSTEPPING) - .tag(4) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_NUDGE_NOZZLE)) - #else - .enabled( - #if HAS_BED_PROBE - isPrintingFromMedia() - #endif - ) - .tag(4) .button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - #endif - .tag(5).enabled(1) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_PRINT_SPEED)) - .tag(isPrintingFromMediaPaused() ? 7 : 6) - .enabled( - #if ENABLED(SDSUPPORT) - isPrintingFromMedia() - #endif - ) - .button( BTN_POS(1,3), BTN_SIZE(1,1), isPrintingFromMediaPaused() ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) - .enabled( - #if ENABLED(SDSUPPORT) - isPrintingFromMedia() - #endif - ) - .tag(8). button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_STOP_PRINT)) - .enabled( - #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - 1 - #endif - ) - .tag(9).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(1).colors(action_btn) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #endif + .button( BACK_POS, GET_TEXT_F(MSG_BACK)); } #undef GRID_COLS #undef GRID_ROWS From 7c3909bc3f5ea84a59f7dce4e3a378f7e2c4e5ba Mon Sep 17 00:00:00 2001 From: Neil van Geffen Date: Tue, 28 Apr 2020 18:22:03 +1200 Subject: [PATCH 0320/1454] Save/Load distinct TMC SG thresholds (#17741) --- Marlin/Configuration_adv.h | 6 ++- Marlin/src/module/configuration_store.cpp | 56 +++++++---------------- Marlin/src/module/stepper/trinamic.cpp | 41 ++++------------- 3 files changed, 30 insertions(+), 73 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 86a240e7db..fc3ce9eea2 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2393,7 +2393,11 @@ #define X_STALL_SENSITIVITY 8 #define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY #define Y_STALL_SENSITIVITY 8 - //#define Z_STALL_SENSITIVITY 8 + #define Y2_STALL_SENSITIVITY Y_STALL_SENSITIVITY + #define Z_STALL_SENSITIVITY 8 + #define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY + #define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY + #define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define SPI_ENDSTOPS // TMC2130 only //#define IMPROVE_HOMING_RELIABILITY #endif diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 1582cf7067..25a00224fd 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -37,7 +37,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V77" +#define EEPROM_VERSION "V78" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -135,7 +135,7 @@ typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; -typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t; +typedef struct { int16_t X, Y, Z, X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; // Limit an index to an array size @@ -328,7 +328,7 @@ typedef struct SettingsDataStruct { // tmc_stepper_current_t tmc_stepper_current; // M906 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5 tmc_hybrid_threshold_t tmc_hybrid_threshold; // M913 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5 - tmc_sgt_t tmc_sgt; // M914 X Y Z X2 + tmc_sgt_t tmc_sgt; // M914 X Y Z X2 Y2 Z2 Z3 Z4 tmc_stealth_enabled_t tmc_stealth_enabled; // M569 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5 // @@ -1112,10 +1112,14 @@ void MarlinSettings::postprocess() { { tmc_sgt_t tmc_sgt{0}; #if USE_SENSORLESS - TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()); + TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()); TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold()); - TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()); - TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()); + TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()); + TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold()); + TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()); + TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold()); + TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold()); + TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold()); #endif EEPROM_WRITE(tmc_sgt); } @@ -1929,9 +1933,6 @@ void MarlinSettings::postprocess() { // // TMC StallGuard threshold. - // X and X2 use the same value - // Y and Y2 use the same value - // Z, Z2, Z3 and Z4 use the same value // { tmc_sgt_t tmc_sgt; @@ -1939,37 +1940,14 @@ void MarlinSettings::postprocess() { EEPROM_READ(tmc_sgt); #if USE_SENSORLESS if (!validating) { - #ifdef X_STALL_SENSITIVITY - #if AXIS_HAS_STALLGUARD(X) - stepperX.homing_threshold(tmc_sgt.X); - #endif - #if AXIS_HAS_STALLGUARD(X2) && !X2_SENSORLESS - stepperX2.homing_threshold(tmc_sgt.X); - #endif - #endif + TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)); TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2)); - #ifdef Y_STALL_SENSITIVITY - #if AXIS_HAS_STALLGUARD(Y) - stepperY.homing_threshold(tmc_sgt.Y); - #endif - #if AXIS_HAS_STALLGUARD(Y2) - stepperY2.homing_threshold(tmc_sgt.Y); - #endif - #endif - #ifdef Z_STALL_SENSITIVITY - #if AXIS_HAS_STALLGUARD(Z) - stepperZ.homing_threshold(tmc_sgt.Z); - #endif - #if AXIS_HAS_STALLGUARD(Z2) - stepperZ2.homing_threshold(tmc_sgt.Z); - #endif - #if AXIS_HAS_STALLGUARD(Z3) - stepperZ3.homing_threshold(tmc_sgt.Z); - #endif - #if AXIS_HAS_STALLGUARD(Z4) - stepperZ4.homing_threshold(tmc_sgt.Z); - #endif - #endif + TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)); + TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2)); + TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)); + TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2)); + TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3)); + TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4)); } #endif } diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 100d660f2c..4f0751ec2e 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -770,39 +770,14 @@ void reset_trinamic_drivers() { #endif #if USE_SENSORLESS - #if X_SENSORLESS - #if AXIS_HAS_STALLGUARD(X) - stepperX.homing_threshold(X_STALL_SENSITIVITY); - #endif - #if AXIS_HAS_STALLGUARD(X2) && !X2_SENSORLESS - stepperX2.homing_threshold(X_STALL_SENSITIVITY); - #endif - #endif - #if X2_SENSORLESS - stepperX2.homing_threshold(X2_STALL_SENSITIVITY); - #endif - #if Y_SENSORLESS - #if AXIS_HAS_STALLGUARD(Y) - stepperY.homing_threshold(Y_STALL_SENSITIVITY); - #endif - #if AXIS_HAS_STALLGUARD(Y2) - stepperY2.homing_threshold(Y_STALL_SENSITIVITY); - #endif - #endif - #if Z_SENSORLESS - #if AXIS_HAS_STALLGUARD(Z) - stepperZ.homing_threshold(Z_STALL_SENSITIVITY); - #endif - #if AXIS_HAS_STALLGUARD(Z2) - stepperZ2.homing_threshold(Z_STALL_SENSITIVITY); - #endif - #if AXIS_HAS_STALLGUARD(Z3) - stepperZ3.homing_threshold(Z_STALL_SENSITIVITY); - #endif - #if AXIS_HAS_STALLGUARD(Z4) - stepperZ4.homing_threshold(Z_STALL_SENSITIVITY); - #endif - #endif + TERN_(X_SENSORLESS, stepperX.homing_threshold(X_STALL_SENSITIVITY)); + TERN_(X2_SENSORLESS, stepperX2.homing_threshold(X2_STALL_SENSITIVITY)); + TERN_(Y_SENSORLESS, stepperY.homing_threshold(Y_STALL_SENSITIVITY)); + TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(Y2_STALL_SENSITIVITY)); + TERN_(Z_SENSORLESS, stepperZ.homing_threshold(Z_STALL_SENSITIVITY)); + TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(Z2_STALL_SENSITIVITY)); + TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(Z3_STALL_SENSITIVITY)); + TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(Z4_STALL_SENSITIVITY)); #endif #ifdef TMC_ADV From 5f7a75979f8c1f7cf1f3adbb61e862f17409047b Mon Sep 17 00:00:00 2001 From: randellhodges Date: Tue, 28 Apr 2020 02:27:55 -0500 Subject: [PATCH 0321/1454] LPC176x SPI / I2C PersistentStore (#17651) --- Marlin/src/HAL/DUE/EepromEmulation.cpp | 4 +- Marlin/src/HAL/LPC1768/eeprom_wired.cpp | 86 +++++++++++++++++++ Marlin/src/HAL/STM32/eeprom_wired.cpp | 17 +--- Marlin/src/HAL/STM32/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp | 6 +- .../HAL/STM32_F4_F7/inc/Conditionals_post.h | 1 + Marlin/src/HAL/shared/eeprom_i2c.cpp | 54 ++++++------ Marlin/src/HAL/shared/eeprom_spi.cpp | 8 +- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 8 -- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 8 -- Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h | 8 -- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 8 -- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 8 -- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 8 -- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 4 - Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 8 -- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 8 -- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 8 -- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 8 -- Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h | 8 -- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h | 8 -- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h | 8 -- .../pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h | 8 -- .../pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h | 8 -- .../src/pins/lpc1769/pins_COHESION3D_MINI.h | 8 -- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 8 -- Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 8 -- Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h | 8 -- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 8 -- 29 files changed, 132 insertions(+), 210 deletions(-) create mode 100644 Marlin/src/HAL/LPC1768/eeprom_wired.cpp diff --git a/Marlin/src/HAL/DUE/EepromEmulation.cpp b/Marlin/src/HAL/DUE/EepromEmulation.cpp index 66af50cfd2..8be9affa68 100644 --- a/Marlin/src/HAL/DUE/EepromEmulation.cpp +++ b/Marlin/src/HAL/DUE/EepromEmulation.cpp @@ -992,7 +992,7 @@ void eeprom_write_byte(uint8_t* addr, uint8_t value) { ee_Write((uint32_t)addr, value); } -void eeprom_update_block(const void* __src, void* __dst, size_t __n) { +void eeprom_update_block(const void *__src, void *__dst, size_t __n) { uint8_t* dst = (uint8_t*)__dst; const uint8_t* src = (const uint8_t*)__src; while (__n--) { @@ -1002,7 +1002,7 @@ void eeprom_update_block(const void* __src, void* __dst, size_t __n) { } } -void eeprom_read_block(void* __dst, const void* __src, size_t __n) { +void eeprom_read_block(void *__dst, const void *__src, size_t __n) { uint8_t* dst = (uint8_t*)__dst; uint8_t* src = (uint8_t*)__src; while (__n--) { diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp new file mode 100644 index 0000000000..3395601a24 --- /dev/null +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -0,0 +1,86 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * I2C/SPI EEPROM interface for LPC1768 + */ + +#ifdef TARGET_LPC1768 + +#include "../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +#include "../shared/eeprom_api.h" +#include + +#ifndef EEPROM_SIZE + #define EEPROM_SIZE 0x8000 // 32kB‬ +#endif + +bool PersistentStore::access_start() { + TERN_(SPI_EEPROM, eeprom_init()); + return true; +} + +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t v = *value; + + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + + crc16(crc, &v, 1); + pos++; + value++; + }; + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + // Read from external EEPROM + const uint8_t c = eeprom_read_byte((uint8_t*)pos); + + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +size_t PersistentStore::capacity() { return EEPROM_SIZE; } + +#endif // USE_WIRED_EEPROM +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index cd0f93e8d8..b83a2eb2bb 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -28,13 +28,8 @@ #include "../shared/eeprom_api.h" -bool PersistentStore::access_start() { - return true; -} - -bool PersistentStore::access_finish() { - return true; -} +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { @@ -84,13 +79,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t } size_t PersistentStore::capacity() { - return ( - #if USE_WIRED_EEPROM - E2END + 1 - #else - 4096 // 4kB - #endif - ); + return TERN(USE_WIRED_EEPROM, E2END + 1, 4096); // 4K for emulated } #endif // USE_WIRED_EEPROM || SRAM_EEPROM_EMULATION diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index 32ad3a57b9..27e814a0a6 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -21,7 +21,7 @@ */ #pragma once -// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation +// If no real or emulated EEPROM selected, fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp index cc1a1bb01e..3249ef2b7c 100644 --- a/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp @@ -80,7 +80,7 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) { HAL_FLASH_Unlock(); __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - uint16_t eeprom_address = unsigned(pos); + const unsigned eeprom_address = (unsigned)pos; if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK) for (;;) HAL_Delay(1); // Spin forever until watchdog reset @@ -91,7 +91,7 @@ uint8_t eeprom_read_byte(uint8_t *pos) { eeprom_init(); uint16_t data = 0xFF; - uint16_t eeprom_address = unsigned(pos); + const unsigned eeprom_address = (unsigned)pos; (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error return uint8_t(data); @@ -101,7 +101,7 @@ void eeprom_read_block(void *__dst, const void *__src, size_t __n) { eeprom_init(); uint16_t data = 0xFF; - uint16_t eeprom_address = unsigned(__src); + const unsigned eeprom_address = (unsigned)__src; LOOP_L_N(c, __n) { EE_ReadVariable(eeprom_address+c, &data); *((uint8_t*)__dst + c) = data; diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h index d21624955e..a96352376e 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h @@ -26,4 +26,5 @@ #undef SRAM_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION + #warning "Forcing use of FLASH_EEPROM_EMULATION." #endif diff --git a/Marlin/src/HAL/shared/eeprom_i2c.cpp b/Marlin/src/HAL/shared/eeprom_i2c.cpp index 8ce3b88c48..cc60c8d196 100644 --- a/Marlin/src/HAL/shared/eeprom_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_i2c.cpp @@ -35,44 +35,50 @@ #include "../HAL.h" #include +#ifndef EEPROM_WRITE_DELAY + #define EEPROM_WRITE_DELAY 5 +#endif + // ------------------------ // Private Variables // ------------------------ -static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(0x50); +#ifndef EEPROM_DEVICE_ADDRESS + #define EEPROM_DEVICE_ADDRESS 0x50 +#endif + +static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRESS); // ------------------------ // Public functions // ------------------------ -static void eeprom_init() { - Wire.begin(); -} +static void eeprom_init() { Wire.begin(); } void eeprom_write_byte(uint8_t *pos, unsigned char value) { - unsigned eeprom_address = (unsigned) pos; - - eeprom_init(); + const unsigned eeprom_address = (unsigned)pos; Wire.beginTransmission(eeprom_device_address); - Wire.write((int)(eeprom_address >> 8)); // MSB - Wire.write((int)(eeprom_address & 0xFF)); // LSB + Wire.write(int(eeprom_address >> 8)); // MSB + Wire.write(int(eeprom_address & 0xFF)); // LSB Wire.write(value); Wire.endTransmission(); // wait for write cycle to complete // this could be done more efficiently with "acknowledge polling" - delay(5); + delay(EEPROM_WRITE_DELAY); } // WARNING: address is a page address, 6-bit end will wrap around // also, data can be maximum of about 30 bytes, because the Wire library has a buffer of 32 bytes -void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) { +void eeprom_update_block(const void *pos, void *__dst, size_t n) { + const unsigned eeprom_address = (unsigned)__dst; + eeprom_init(); Wire.beginTransmission(eeprom_device_address); - Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB - Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB + Wire.write(int(eeprom_address >> 8)); // MSB + Wire.write(int(eeprom_address & 0xFF)); // LSB Wire.endTransmission(); uint8_t *ptr = (uint8_t*)pos; @@ -83,37 +89,37 @@ void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) { if (flag) { Wire.beginTransmission(eeprom_device_address); - Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB - Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB + Wire.write(int(eeprom_address >> 8)); // MSB + Wire.write(int(eeprom_address & 0xFF)); // LSB Wire.write((uint8_t*)pos, n); Wire.endTransmission(); // wait for write cycle to complete // this could be done more efficiently with "acknowledge polling" - delay(5); + delay(EEPROM_WRITE_DELAY); } } uint8_t eeprom_read_byte(uint8_t *pos) { - unsigned eeprom_address = (unsigned)pos; - - eeprom_init(); + const unsigned eeprom_address = (unsigned)pos; Wire.beginTransmission(eeprom_device_address); - Wire.write((int)(eeprom_address >> 8)); // MSB - Wire.write((int)(eeprom_address & 0xFF)); // LSB + Wire.write(int(eeprom_address >> 8)); // MSB + Wire.write(int(eeprom_address & 0xFF)); // LSB Wire.endTransmission(); Wire.requestFrom(eeprom_device_address, (byte)1); return Wire.available() ? Wire.read() : 0xFF; } // Don't read more than 30..32 bytes at a time! -void eeprom_read_block(void* pos, const void* eeprom_address, size_t n) { +void eeprom_read_block(void* pos, const void *__dst, size_t n) { + const unsigned eeprom_address = (unsigned)__dst; + eeprom_init(); Wire.beginTransmission(eeprom_device_address); - Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB - Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB + Wire.write(int(eeprom_address >> 8)); // MSB + Wire.write(int(eeprom_address & 0xFF)); // LSB Wire.endTransmission(); Wire.requestFrom(eeprom_device_address, (byte)n); for (byte c = 0; c < n; c++ ) diff --git a/Marlin/src/HAL/shared/eeprom_spi.cpp b/Marlin/src/HAL/shared/eeprom_spi.cpp index ce7479aedb..73602feaaf 100644 --- a/Marlin/src/HAL/shared/eeprom_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_spi.cpp @@ -35,6 +35,10 @@ #define CMD_READ 2 // WRITE #define CMD_WRITE 2 // WRITE +#ifndef EEPROM_WRITE_DELAY + #define EEPROM_WRITE_DELAY 7 +#endif + uint8_t eeprom_read_byte(uint8_t* pos) { uint8_t v; uint8_t eeprom_temp[3]; @@ -90,7 +94,7 @@ void eeprom_write_byte(uint8_t* pos, uint8_t value) { spiSend(SPI_CHAN_EEPROM1, value); WRITE(SPI_EEPROM1_CS, HIGH); - delay(7); // wait for page write to complete + delay(EEPROM_WRITE_DELAY); // wait for page write to complete } void eeprom_update_block(const void* src, void* eeprom_address, size_t n) { @@ -112,7 +116,7 @@ void eeprom_update_block(const void* src, void* eeprom_address, size_t n) { spiSend(SPI_CHAN_EEPROM1, (const uint8_t*)src, n); WRITE(SPI_EEPROM1_CS, HIGH); - delay(7); // wait for page write to complete + delay(EEPROM_WRITE_DELAY); // wait for page write to complete } #endif // SPI_EEPROM diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index bba63febd9..4561ff0163 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -31,14 +31,6 @@ #define BOARD_INFO_NAME "AZSMZ MINI" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index fa3a2cc844..75dcbe06c9 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -38,14 +38,6 @@ #define BOARD_INFO_NAME "BIQU Thunder B300 V1.0" #endif -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Limit Switches // diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index eb384f4566..98ce887886 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -36,14 +36,6 @@ #define BOARD_INFO_NAME "BIQU BQ111-A4" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Limit Switches // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 4a029db60f..391f475fef 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -23,14 +23,6 @@ #define BOARD_INFO_NAME "BIGTREE SKR 1.1" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Limit Switches // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index a9d333721f..48b9711366 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -23,14 +23,6 @@ #define BOARD_INFO_NAME "BIGTREE SKR 1.3" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Trinamic Stallguard pins // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 5004d166cd..85e477a5c2 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -25,14 +25,6 @@ #define BOARD_INFO_NAME "BIGTREE SKR 1.4" #endif -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // SD Connection // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 63e160d8a0..2ca8f86f1d 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -32,10 +32,6 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if DISABLED(SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION -#endif - // // Steppers // diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index b272575e19..8ff565fa8f 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -30,14 +30,6 @@ // Ignore temp readings during develpment. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Enable 12MHz clock output on P1.27 pin to sync TMC2208 chip clocks // diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 0cd10ebc05..054f155117 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -38,14 +38,6 @@ #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SBASE" #endif -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - #define LED_PIN P1_18 // Used as a status indicator #define LED2_PIN P1_19 #define LED3_PIN P1_20 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index f8fd0afcd3..5a8e1ad635 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -32,14 +32,6 @@ #define BOARD_INFO_NAME "MKS SGen-L" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN_L" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index f4acfb7ba1..9a74419363 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -42,14 +42,6 @@ #define BOARD_INFO_NAME "Re-ARM RAMPS 1.4" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 5e2b10ef6f..df7665f0ee 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -32,14 +32,6 @@ #define BOARD_INFO_NAME "Selena Compact" #define BOARD_WEBSITE_URL "github.com/Ales2-k/Selena" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index 5df52908f4..4296f69274 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -32,14 +32,6 @@ #define BOARD_INFO_NAME "Azteeg X5 GT" #define BOARD_WEBSITE_URL "tinyurl.com/yx8tdqa3" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index ba1351e6f4..306688bef3 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -187,14 +187,6 @@ #endif // HAS_SPI_LCD -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // SD Support // diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h index e16a1b90b6..4b731ae9d3 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h @@ -31,14 +31,6 @@ #define BOARD_INFO_NAME "Azteeg X5 MINI WIFI" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // DIGIPOT slave addresses // diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h index 974537ee11..937ba56bb7 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h @@ -24,14 +24,6 @@ #define BOARD_INFO_NAME "BIGTREE SKR 1.4 TURBO" #define SKR_HAS_LPC1769 -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Include SKR 1.4 pins // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index adb3bc04f5..9efddf210a 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -31,14 +31,6 @@ #define BOARD_INFO_NAME "Cohesion3D Mini" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index c9b13b234e..a32e55db92 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -31,14 +31,6 @@ #define BOARD_INFO_NAME "Cohesion3D ReMix" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index 713eca2944..e683c4e423 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -32,14 +32,6 @@ #define BOARD_INFO_NAME "MKS SGen" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - #define MKS_HAS_LPC1769 #include "../lpc1768/pins_MKS_SBASE.h" diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index 0a3be9aff4..6b147740a4 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -32,14 +32,6 @@ #define BOARD_INFO_NAME "Smoothieboard" #define BOARD_WEBSITE_URL "smoothieware.org/smoothieboard" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 0836e1ff5a..bb03335c57 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -32,14 +32,6 @@ #define BOARD_INFO_NAME "TH3D EZBoard" #define BOARD_WEBSITE_URL "th3dstudio.com" -// -// EEPROM -// -#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - //#define SDCARD_EEPROM_EMULATION -#endif - // // Servos // From 2c959123e5972920bfb40ac519bfaa5b0b7c6d67 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 04:31:59 -0500 Subject: [PATCH 0322/1454] Clean up whitespace --- Marlin/src/HAL/AVR/HAL.cpp | 1 - Marlin/src/HAL/AVR/watchdog.cpp | 1 - Marlin/src/HAL/DUE/DebugMonitor.cpp | 1 - Marlin/src/HAL/DUE/watchdog.cpp | 1 - Marlin/src/HAL/ESP32/HAL.cpp | 1 - Marlin/src/HAL/ESP32/HAL_SPI.cpp | 1 - Marlin/src/HAL/ESP32/eeprom.cpp | 1 - Marlin/src/HAL/ESP32/spiffs.cpp | 1 - Marlin/src/HAL/ESP32/timers.cpp | 1 - Marlin/src/HAL/ESP32/watchdog.cpp | 1 - Marlin/src/HAL/ESP32/web.cpp | 1 - Marlin/src/HAL/ESP32/wifi.cpp | 1 - Marlin/src/HAL/LINUX/HAL.cpp | 1 - Marlin/src/HAL/LINUX/arduino.cpp | 1 - Marlin/src/HAL/LINUX/eeprom.cpp | 1 - Marlin/src/HAL/LINUX/hardware/Clock.cpp | 1 - Marlin/src/HAL/LINUX/hardware/Gpio.cpp | 1 - Marlin/src/HAL/LINUX/hardware/Heater.cpp | 1 - Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp | 1 - Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp | 1 - Marlin/src/HAL/LINUX/hardware/Timer.cpp | 1 - Marlin/src/HAL/LINUX/include/pinmapping.cpp | 1 - Marlin/src/HAL/LINUX/main.cpp | 1 - Marlin/src/HAL/LINUX/timers.cpp | 1 - Marlin/src/HAL/LINUX/watchdog.cpp | 1 - Marlin/src/HAL/LPC1768/DebugMonitor.cpp | 1 - Marlin/src/HAL/LPC1768/HAL.cpp | 1 - Marlin/src/HAL/LPC1768/MarlinSerial.cpp | 1 - Marlin/src/HAL/LPC1768/fast_pwm.cpp | 1 - Marlin/src/HAL/LPC1768/usb_serial.cpp | 1 - Marlin/src/HAL/LPC1768/watchdog.cpp | 1 - Marlin/src/HAL/SAMD51/HAL.cpp | 1 - Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp | 1 - Marlin/src/HAL/SAMD51/eeprom_flash.cpp | 1 - Marlin/src/HAL/SAMD51/timers.cpp | 1 - Marlin/src/HAL/SAMD51/watchdog.cpp | 1 - Marlin/src/HAL/STM32F1/Servo.cpp | 1 - Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 1 - Marlin/src/HAL/STM32F1/sdio.cpp | 1 - Marlin/src/HAL/TEENSY31_32/watchdog.cpp | 1 - Marlin/src/feature/mmu2/mmu2.cpp | 8 ++++---- Marlin/src/feature/tmc_util.h | 2 +- Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h | 4 ++-- Marlin/src/module/planner.cpp | 1 - 44 files changed, 7 insertions(+), 48 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 317d13a540..05d4e51dd0 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __AVR__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/AVR/watchdog.cpp b/Marlin/src/HAL/AVR/watchdog.cpp index e35a70f2cc..ef1ed0e596 100644 --- a/Marlin/src/HAL/AVR/watchdog.cpp +++ b/Marlin/src/HAL/AVR/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __AVR__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/DUE/DebugMonitor.cpp b/Marlin/src/HAL/DUE/DebugMonitor.cpp index 3ed9873e66..84ea137ad7 100644 --- a/Marlin/src/HAL/DUE/DebugMonitor.cpp +++ b/Marlin/src/HAL/DUE/DebugMonitor.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_SAM #include "../../core/macros.h" diff --git a/Marlin/src/HAL/DUE/watchdog.cpp b/Marlin/src/HAL/DUE/watchdog.cpp index c245633d76..2fa6ea5e5d 100644 --- a/Marlin/src/HAL/DUE/watchdog.cpp +++ b/Marlin/src/HAL/DUE/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_SAM #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 641925a294..4194c531cf 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "HAL.h" diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 981d9b49c1..27414cf6f8 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "HAL.h" diff --git a/Marlin/src/HAL/ESP32/eeprom.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp index 1c005ff3d4..8b75dc51e8 100644 --- a/Marlin/src/HAL/ESP32/eeprom.cpp +++ b/Marlin/src/HAL/ESP32/eeprom.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/ESP32/spiffs.cpp b/Marlin/src/HAL/ESP32/spiffs.cpp index 0013dd6093..69fe7da58e 100644 --- a/Marlin/src/HAL/ESP32/spiffs.cpp +++ b/Marlin/src/HAL/ESP32/spiffs.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp index ef181a438c..ad897661c6 100644 --- a/Marlin/src/HAL/ESP32/timers.cpp +++ b/Marlin/src/HAL/ESP32/timers.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include diff --git a/Marlin/src/HAL/ESP32/watchdog.cpp b/Marlin/src/HAL/ESP32/watchdog.cpp index 9f681e6095..073da7f69d 100644 --- a/Marlin/src/HAL/ESP32/watchdog.cpp +++ b/Marlin/src/HAL/ESP32/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/ESP32/web.cpp b/Marlin/src/HAL/ESP32/web.cpp index b795efe3c5..7c175bcc9b 100644 --- a/Marlin/src/HAL/ESP32/web.cpp +++ b/Marlin/src/HAL/ESP32/web.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/ESP32/wifi.cpp b/Marlin/src/HAL/ESP32/wifi.cpp index 9203dd62e7..9ac3ddde24 100644 --- a/Marlin/src/HAL/ESP32/wifi.cpp +++ b/Marlin/src/HAL/ESP32/wifi.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_ESP32 #include "../../core/serial.h" diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index d38644f1a5..dd12d8645f 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 008db15592..d9fa84ac7c 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include diff --git a/Marlin/src/HAL/LINUX/eeprom.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp index 4745f05673..7a9a1db381 100644 --- a/Marlin/src/HAL/LINUX/eeprom.cpp +++ b/Marlin/src/HAL/LINUX/eeprom.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LINUX/hardware/Clock.cpp b/Marlin/src/HAL/LINUX/hardware/Clock.cpp index 8265fedbf0..8fd4825b35 100644 --- a/Marlin/src/HAL/LINUX/hardware/Clock.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Clock.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "../../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LINUX/hardware/Gpio.cpp b/Marlin/src/HAL/LINUX/hardware/Gpio.cpp index e49fb13754..b7b12ceb16 100644 --- a/Marlin/src/HAL/LINUX/hardware/Gpio.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Gpio.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "Gpio.h" diff --git a/Marlin/src/HAL/LINUX/hardware/Heater.cpp b/Marlin/src/HAL/LINUX/hardware/Heater.cpp index 7c9bfaf80f..8fc8555243 100644 --- a/Marlin/src/HAL/LINUX/hardware/Heater.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Heater.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "Clock.h" diff --git a/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp index a79f14f6f5..fe6e130f36 100644 --- a/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp +++ b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "IOLoggerCSV.h" diff --git a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp index ec58fe77e5..ee7602db62 100644 --- a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp +++ b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include diff --git a/Marlin/src/HAL/LINUX/hardware/Timer.cpp b/Marlin/src/HAL/LINUX/hardware/Timer.cpp index e7136bbdef..e213cc2683 100644 --- a/Marlin/src/HAL/LINUX/hardware/Timer.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Timer.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "Timer.h" diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp index 0340e681fe..66d8acd2f6 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.cpp +++ b/Marlin/src/HAL/LINUX/include/pinmapping.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp index 1155f2a873..1217da3905 100644 --- a/Marlin/src/HAL/LINUX/main.cpp +++ b/Marlin/src/HAL/LINUX/main.cpp @@ -17,7 +17,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ extern void setup(); diff --git a/Marlin/src/HAL/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp index ebfb950595..4ccffa63c5 100644 --- a/Marlin/src/HAL/LINUX/timers.cpp +++ b/Marlin/src/HAL/LINUX/timers.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "hardware/Timer.h" diff --git a/Marlin/src/HAL/LINUX/watchdog.cpp b/Marlin/src/HAL/LINUX/watchdog.cpp index 5ffe860f05..03af3cae7b 100644 --- a/Marlin/src/HAL/LINUX/watchdog.cpp +++ b/Marlin/src/HAL/LINUX/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __PLAT_LINUX__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp index ce9ffec70c..5df527bdb3 100644 --- a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp +++ b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef TARGET_LPC1768 #include "../../core/macros.h" diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index cfa7afd284..5a7e55eb10 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp index 1b80b211fb..370aafdd9b 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index 4f2e30ee72..b2f989bd50 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp index ddb31da20f..3438f50c30 100644 --- a/Marlin/src/HAL/LPC1768/usb_serial.cpp +++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/LPC1768/watchdog.cpp b/Marlin/src/HAL/LPC1768/watchdog.cpp index 73563a6baa..75d386d923 100644 --- a/Marlin/src/HAL/LPC1768/watchdog.cpp +++ b/Marlin/src/HAL/LPC1768/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index ea5ebd6d64..8b39825171 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -18,7 +18,6 @@ * along with this program. If not, see . * */ - #ifdef __SAMD51__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp index f13b29555a..eeaf2e8a1a 100644 --- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp +++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp @@ -18,7 +18,6 @@ * along with this program. If not, see . * */ - #ifdef ADAFRUIT_GRAND_CENTRAL_M4 /** diff --git a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp index fd8973369a..c8a1718285 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp @@ -18,7 +18,6 @@ * along with this program. If not, see . * */ - #ifdef __SAMD51__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index 158ea4ed17..4560e2e674 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -18,7 +18,6 @@ * along with this program. If not, see . * */ - #ifdef __SAMD51__ // -------------------------------------------------------------------------- diff --git a/Marlin/src/HAL/SAMD51/watchdog.cpp b/Marlin/src/HAL/SAMD51/watchdog.cpp index 13539b4d70..f8dd5c4fb8 100644 --- a/Marlin/src/HAL/SAMD51/watchdog.cpp +++ b/Marlin/src/HAL/SAMD51/watchdog.cpp @@ -18,7 +18,6 @@ * along with this program. If not, see . * */ - #ifdef __SAMD51__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index da0a7cf1be..e5aa9f21e7 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #ifdef __STM32F1__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index ed5d50cbde..8527f175a6 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -17,7 +17,6 @@ * along with this program. If not, see . * */ - #ifdef __STM32F1__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index da6beda85c..af53635ac4 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #ifdef ARDUINO_ARCH_STM32F1 #include diff --git a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp index 618294591b..26f722896c 100644 --- a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp +++ b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #ifdef __MK20DX256__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 3bb5d9e7ee..6c61b714f7 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -301,7 +301,7 @@ void MMU2::mmu_loop() { tx_str_P(PSTR("P0\n")); state = 2; // wait for response } - + TERN_(PRUSA_MMU2_S_MODE, check_filament()); break; @@ -672,13 +672,13 @@ void MMU2::filament_runout() { if (runout && !mmu2s_triggered) { DEBUG_ECHOLNPGM("MMU <= 'A'"); tx_str_P(PSTR("A\n")); - } + } mmu2s_triggered = runout; } bool MMU2::can_load() { execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence)); - + int filament_detected_count = 0; const int steps = MMU2_CAN_LOAD_RETRACT / MMU2_CAN_LOAD_INCREMENT; DEBUG_ECHOLNPGM("MMU can_load:"); @@ -689,7 +689,7 @@ void MMU2::filament_runout() { if (mmu2s_triggered) ++filament_detected_count; } - if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION / MMU2_CAN_LOAD_INCREMENT)) { + if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION / MMU2_CAN_LOAD_INCREMENT)) { DEBUG_ECHOLNPGM(" failed."); return false; } diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index d7b6a944df..73e9109ea2 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -100,7 +100,7 @@ class TMCMarlin : public TMC, public TMCStorage { TMC::rms_current(mA, mult); } inline uint16_t get_microstep_counter() { return TMC::MSCNT(); } - + #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return this->en_pwm_mode(); } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index ed9affba23..2187ebd8ee 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -30,8 +30,8 @@ #ifdef CHEETAH_TFT_PINMAP #ifndef __MARLIN_FIRMWARE__ #error "This pin mapping requires Marlin." - #endif - + #endif + #define CLCD_SPI_BUS 2 #define CLCD_MOD_RESET PC9 diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 4e675f075d..117a8b6fda 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2862,7 +2862,6 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { #if ENABLED(AUTOTEMP) void Planner::autotemp_update() { - #if ENABLED(AUTOTEMP_PROPORTIONAL) const int16_t target = thermalManager.degTargetHotend(active_extruder); autotemp_min = target + AUTOTEMP_MIN_P; From 56e3106b631a77c3768369364a7d1d832c97f5dc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 07:52:31 -0500 Subject: [PATCH 0323/1454] Clean up whitespace --- Marlin/src/HAL/STM32/HAL.cpp | 1 - Marlin/src/HAL/STM32/eeprom_flash.cpp | 1 - Marlin/src/HAL/STM32/timers.cpp | 1 - Marlin/src/HAL/STM32/watchdog.cpp | 1 - Marlin/src/HAL/STM32_F4_F7/HAL.cpp | 1 - Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp | 1 - Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp | 1 - Marlin/src/HAL/STM32_F4_F7/Servo.cpp | 1 - Marlin/src/HAL/STM32_F4_F7/eeprom.cpp | 1 - Marlin/src/HAL/STM32_F4_F7/watchdog.cpp | 1 - Marlin/src/HAL/TEENSY35_36/eeprom.cpp | 1 - Marlin/src/HAL/TEENSY35_36/watchdog.cpp | 1 - Marlin/src/HAL/shared/backtrace/backtrace.cpp | 1 - 13 files changed, 13 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index f49856189b..f146d7a87b 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "HAL.h" diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 39012f8205..765e847420 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index b7b65f714e..ad46e34b71 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "HAL.h" diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp index 2c6b583e83..3416a353f6 100644 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ b/Marlin/src/HAL/STM32/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp index 5acda8af41..52fa4f8762 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) #include "HAL.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp index ffd46dae60..bdd01bc814 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && defined(STM32F4) #include "../HAL.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp index d90f22e03a..6a9285f3da 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && defined(STM32F7) #include "../HAL.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp index e2b1b9fdac..c391282f6a 100644 --- a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp index b957aae6a8..0b0aa4475e 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp index 347edcd49d..538aea55b9 100644 --- a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index 0ee686de13..bd597c2ded 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -20,7 +20,6 @@ * along with this program. If not, see . * */ - #if defined(__MK64FX512__) || defined(__MK66FX1M0__) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp index 69afa04a54..5a9d4816f5 100644 --- a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp +++ b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(__MK64FX512__) || defined(__MK66FX1M0__) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.cpp b/Marlin/src/HAL/shared/backtrace/backtrace.cpp index 7264969c74..b41404f4d0 100644 --- a/Marlin/src/HAL/shared/backtrace/backtrace.cpp +++ b/Marlin/src/HAL/shared/backtrace/backtrace.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(__arm__) || defined(__thumb__) #include "backtrace.h" From 4b35ff1f070619ff455830ffb9b08cb1741a20a2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 07:48:32 -0500 Subject: [PATCH 0324/1454] STEPPER_TIMER_RATE might call a function --- Marlin/src/module/stepper.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index c105570067..92ee753392 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -416,10 +416,10 @@ xyze_int8_t Stepper::count_direction{0}; #endif #define CYCLES_TO_NS(CYC) (1000UL * (CYC) / ((F_CPU) / 1000000)) -constexpr uint32_t NS_PER_PULSE_TIMER_TICK = 1000000000UL / (STEPPER_TIMER_RATE); +#define NS_PER_PULSE_TIMER_TICK (1000000000UL / (STEPPER_TIMER_RATE)) // Round up when converting from ns to timer ticks -constexpr uint32_t NS_TO_PULSE_TIMER_TICKS(uint32_t NS) { return (NS + (NS_PER_PULSE_TIMER_TICK) / 2) / (NS_PER_PULSE_TIMER_TICK); } +#define NS_TO_PULSE_TIMER_TICKS(NS) (((NS) + (NS_PER_PULSE_TIMER_TICK) / 2) / (NS_PER_PULSE_TIMER_TICK)) #define TIMER_SETUP_NS (CYCLES_TO_NS(TIMER_READ_ADD_AND_STORE_CYCLES)) From bd82b8bc7ee506d89a99a408fccdad5853ab39b6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 08:30:52 -0500 Subject: [PATCH 0325/1454] Suppress compile warnings --- Marlin/src/MarlinCore.cpp | 5 +++++ Marlin/src/gcode/queue.cpp | 6 ++++++ 2 files changed, 11 insertions(+) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 28a1b0c98f..26a7fb0684 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -285,6 +285,9 @@ void setup_powerhold() { #include "pins/sensitive_pins.h" +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wnarrowing" + bool pin_is_protected(const pin_t pin) { static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; LOOP_L_N(i, COUNT(sensitive_pins)) { @@ -295,6 +298,8 @@ bool pin_is_protected(const pin_t pin) { return false; } +#pragma GCC diagnostic pop + void protected_pin_err() { SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN); } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 7c4dc08486..4d7d107ebd 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -216,8 +216,14 @@ bool GCodeQueue::process_injected_command() { gcode.process_parsed_command(); } + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wrestrict" + // Copy the next command into place strcpy(injected_commands, &injected_commands[i + (c != '\0')]); + + #pragma GCC diagnostic pop + return true; } From e7a6a52eda99a0575584ca2b1f83f8e38db0142c Mon Sep 17 00:00:00 2001 From: Stephan Date: Wed, 29 Apr 2020 01:12:56 +0200 Subject: [PATCH 0326/1454] Use center defines for Z Safe Homing XY (#17782) --- Marlin/Configuration.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 38c4ae4c94..9564cad8a4 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1368,8 +1368,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28). + #define Z_SAFE_HOMING_X_POINT X_CENTER // X point for Z homing when homing all axes (G28). + #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing when homing all axes (G28). #endif // Homing speeds (mm/m) From 1d714512f088a3f5afb8ffd1d946cdb03b4b11bb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 18:42:31 -0500 Subject: [PATCH 0327/1454] Fix undefined Z stall --- Marlin/src/inc/Conditionals_post.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 5d5d4321a9..844b291429 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1508,6 +1508,9 @@ // Disable Z axis sensorless homing if a probe is used to home the Z axis #if HOMING_Z_WITH_PROBE #undef Z_STALL_SENSITIVITY + #undef Z2_STALL_SENSITIVITY + #undef Z3_STALL_SENSITIVITY + #undef Z4_STALL_SENSITIVITY #endif #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) #define X_SENSORLESS 1 From f03f76ecfb9c5b23e2ae17734ac8fbdf1c10c44e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 19:17:35 -0500 Subject: [PATCH 0328/1454] Fix info menu without leveling Fixes #17664 --- Marlin/src/lcd/menu/menu_info.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 78153a594b..ef269f7088 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -243,13 +243,15 @@ void menu_info_board() { STATIC_ITEM_P(PSTR(MACHINE_NAME)); // My3DPrinter STATIC_ITEM_P(PSTR(WEBSITE_URL)); // www.my3dprinter.com VALUE_ITEM_P(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); // Extruders: 2 - STATIC_ITEM( - TERN_(AUTO_BED_LEVELING_3POINT, MSG_3POINT_LEVELING) // 3-Point Leveling - TERN_(AUTO_BED_LEVELING_LINEAR, MSG_LINEAR_LEVELING) // Linear Leveling - TERN_(AUTO_BED_LEVELING_BILINEAR, MSG_BILINEAR_LEVELING) // Bi-linear Leveling - TERN_(AUTO_BED_LEVELING_UBL, MSG_UBL_LEVELING) // Unified Bed Leveling - TERN_(MESH_BED_LEVELING, MSG_MESH_LEVELING) // Mesh Leveling - ); + #if HAS_BED_LEVELING + STATIC_ITEM( + TERN_(AUTO_BED_LEVELING_3POINT, MSG_3POINT_LEVELING) // 3-Point Leveling + TERN_(AUTO_BED_LEVELING_LINEAR, MSG_LINEAR_LEVELING) // Linear Leveling + TERN_(AUTO_BED_LEVELING_BILINEAR, MSG_BILINEAR_LEVELING) // Bi-linear Leveling + TERN_(AUTO_BED_LEVELING_UBL, MSG_UBL_LEVELING) // Unified Bed Leveling + TERN_(MESH_BED_LEVELING, MSG_MESH_LEVELING) // Mesh Leveling + ); + #endif END_SCREEN(); } From 3d3d2a923b733be0b9ad4aa2c5c596a6bb5f93f0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Apr 2020 19:14:43 -0500 Subject: [PATCH 0329/1454] Cleanup with updated macros --- Marlin/src/feature/bedlevel/bedlevel.cpp | 20 ++------- Marlin/src/lcd/extui/ui_api.cpp | 56 ++++++------------------ Marlin/src/sd/cardreader.h | 1 + 3 files changed, 19 insertions(+), 58 deletions(-) diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 59e0a6fba6..2d598a545c 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -47,17 +47,9 @@ #endif bool leveling_is_valid() { - return - #if ENABLED(MESH_BED_LEVELING) - mbl.has_mesh() - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - !!bilinear_grid_spacing.x - #elif ENABLED(AUTO_BED_LEVELING_UBL) - ubl.mesh_is_valid() - #else // 3POINT, LINEAR - true - #endif - ; + return TERN1(MESH_BED_LEVELING, mbl.has_mesh()) + && TERN1(AUTO_BED_LEVELING_BILINEAR, !!bilinear_grid_spacing.x) + && TERN1(AUTO_BED_LEVELING_UBL, ubl.mesh_is_valid()); } /** @@ -69,11 +61,7 @@ bool leveling_is_valid() { */ void set_bed_leveling_enabled(const bool enable/*=true*/) { - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - const bool can_change = (!enable || leveling_is_valid()); - #else - constexpr bool can_change = true; - #endif + const bool can_change = TERN1(AUTO_BED_LEVELING_BILINEAR, !enable || leveling_is_valid()); if (can_change && enable != planner.leveling_active) { diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index a9536c68cd..e23674f2cf 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -70,9 +70,6 @@ #if ENABLED(SDSUPPORT) #include "../../sd/cardreader.h" - #define IFSD(A,B) (A) -#else - #define IFSD(A,B) (B) #endif #if HAS_TRINAMIC_CONFIG @@ -164,8 +161,7 @@ namespace ExtUI { } void yield() { - if (!flags.printer_killed) - thermalManager.manage_heater(); + if (!flags.printer_killed) thermalManager.manage_heater(); } void enableHeater(const extruder_t extruder) { @@ -180,13 +176,9 @@ namespace ExtUI { #if HEATER_IDLE_HANDLER switch (heater) { #if HAS_HEATED_BED - case BED: - thermalManager.reset_bed_idle_timer(); - return; - #endif - #if HAS_HEATED_CHAMBER - case CHAMBER: return; // Chamber has no idle timer + case BED: thermalManager.reset_bed_idle_timer(); return; #endif + TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return); // Chamber has no idle timer default: TERN_(HAS_HOTEND, thermalManager.reset_hotend_idle_timer(heater - H0)); break; @@ -233,28 +225,21 @@ namespace ExtUI { #endif bool isHeaterIdle(const extruder_t extruder) { - return false - #if HAS_HOTEND && HEATER_IDLE_HANDLER - || thermalManager.hotend_idle[extruder - E0].timed_out - #else - ; UNUSED(extruder) - #endif - ; + #if HAS_HOTEND && HEATER_IDLE_HANDLER + return thermalManager.hotend_idle[extruder - E0].timed_out + #else + UNUSED(extruder); + return false; + #endif } bool isHeaterIdle(const heater_t heater) { #if HEATER_IDLE_HANDLER switch (heater) { TERN_(HAS_HEATED_BED, case BED: return thermalManager.bed_idle.timed_out); - #if HAS_HEATED_CHAMBER - case CHAMBER: return false; // Chamber has no idle timer - #endif + TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return false); // Chamber has no idle timer default: - #if HAS_HOTEND - return thermalManager.hotend_idle[heater - H0].timed_out; - #else - return false; - #endif + return TERN0(HAS_HOTEND, thermalManager.hotend_idle[heater - H0].timed_out); } #else UNUSED(heater); @@ -311,22 +296,13 @@ namespace ExtUI { } float getAxisPosition_mm(const axis_t axis) { - return - #if ENABLED(JOYSTICK) - flags.jogging ? destination[axis] : - #endif - current_position[axis]; + return TERN_(JOYSTICK, flags.jogging ? destination[axis] :) current_position[axis]; } float getAxisPosition_mm(const extruder_t extruder) { const extruder_t old_tool = getActiveTool(); setActiveTool(extruder, true); - const float epos = ( - #if ENABLED(JOYSTICK) - flags.jogging ? destination.e : - #endif - current_position.e - ); + const float epos = TERN_(JOYSTICK, flags.jogging ? destination.e :) current_position.e; setActiveTool(old_tool, true); return epos; } @@ -1037,11 +1013,7 @@ namespace ExtUI { } bool FileList::isAtRootDir() { - return (true - #if ENABLED(SDSUPPORT) - && card.flag.workDirIsRoot - #endif - ); + return IFSD(card.flag.workDirIsRoot, true); } void FileList::upDir() { diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index b5723694a9..acaabf2deb 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -30,6 +30,7 @@ #endif #define SD_ORDER(N,C) (TERN(SDCARD_RATHERRECENTFIRST, C - 1 - (N), N)) +#define IFSD(A,B) TERN(SDSUPPORT,A,B) #define MAX_DIR_DEPTH 10 // Maximum folder depth #define MAXDIRNAMELENGTH 8 // DOS folder name size From 7b0891b3faa83e4125acdc9561d41e8d301e73df Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 29 Apr 2020 00:20:13 +0000 Subject: [PATCH 0330/1454] [cron] Bump distribution date (2020-04-29) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6cb2ec6e23..e7014c02a4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-28" + #define STRING_DISTRIBUTION_DATE "2020-04-29" #endif /** From 2fbce229100c0be54fa918a43c2d8fdb5654d5f4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 01:47:31 -0500 Subject: [PATCH 0331/1454] Cleanup followup --- Marlin/src/lcd/extui/ui_api.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index e23674f2cf..de043a3198 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -226,7 +226,7 @@ namespace ExtUI { bool isHeaterIdle(const extruder_t extruder) { #if HAS_HOTEND && HEATER_IDLE_HANDLER - return thermalManager.hotend_idle[extruder - E0].timed_out + return thermalManager.hotend_idle[extruder - E0].timed_out; #else UNUSED(extruder); return false; From ef43520d56aab9cf55ad1140b6d1e60f3e648bcf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 03:13:29 -0500 Subject: [PATCH 0332/1454] Disambiguate i2c calls --- Marlin/src/feature/dac/dac_mcp4728.cpp | 2 +- Marlin/src/feature/encoder_i2c.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index 39f873f0cb..2440bcf3fd 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -43,7 +43,7 @@ xyze_uint_t mcp4728_values; */ void mcp4728_init() { Wire.begin(); - Wire.requestFrom(I2C_ADDRESS(DAC_DEV_ADDRESS), 24); + Wire.requestFrom(I2C_ADDRESS(DAC_DEV_ADDRESS), uint8_t(24)); while (Wire.available()) { char deviceID = Wire.read(), hiByte = Wire.read(), diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index dfac6ccdf5..cfac36a5d1 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -305,7 +305,7 @@ int32_t I2CPositionEncoder::get_raw_count() { encoderCount.val = 0x00; - if (Wire.requestFrom(I2C_ADDRESS(i2cAddress), 3) != 3) { + if (Wire.requestFrom(I2C_ADDRESS(i2cAddress), uint8_t(3)) != 3) { //houston, we have a problem... H = I2CPE_MAG_SIG_NF; return 0; @@ -744,7 +744,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) { Wire.endTransmission(); // Read value - if (Wire.requestFrom(I2C_ADDRESS(address), 32)) { + if (Wire.requestFrom(I2C_ADDRESS(address), uint8_t(32))) { char c; while (Wire.available() > 0 && (c = (char)Wire.read()) > 0) SERIAL_ECHO(c); From 36adbfa41c6cd41180e09b0603502df22c17f5eb Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 29 Apr 2020 20:16:13 +1200 Subject: [PATCH 0333/1454] Fix MKS S-Gen standard pins (#17786) Fixes #17783 --- Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 36 ++++++++++--------------- 1 file changed, 14 insertions(+), 22 deletions(-) diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index e683c4e423..293ddce140 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -23,6 +23,10 @@ /** * MKS SGen pin assignments + * + * The pins diagram can be found and the following URL: + * https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf + * */ #ifndef MCU_LPC1769 @@ -35,33 +39,21 @@ #define MKS_HAS_LPC1769 #include "../lpc1768/pins_MKS_SBASE.h" -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN - -//#undef BTN_EN1 -//#undef BTN_EN2 -//#define BTN_EN1 P1_23 // EXP2.5 -//#define BTN_EN2 P1_22 // EXP2.3 - #if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers - * - * The shortage of pins becomes apparent. - * In the worst case you may have to give up the LCD. - * RX pins must be interrupt-capable. */ - #define X_SERIAL_TX_PIN P4_29 // J8-2 - #define X_SERIAL_RX_PIN P4_29 // J8-2 - #define Y_SERIAL_TX_PIN P2_08 // J8-3 - #define Y_SERIAL_RX_PIN P2_08 // J8-3 - - #define Z_SERIAL_TX_PIN P2_11 // J8-4 - #define Z_SERIAL_RX_PIN P2_11 // J8-4 - #define E0_SERIAL_TX_PIN P2_13 // J8-5 - #define E0_SERIAL_RX_PIN P2_13 // J8-5 + #define X_SERIAL_TX_PIN P1_22 // J8-2 + #define X_SERIAL_RX_PIN P1_22 // J8-2 + #define Y_SERIAL_TX_PIN P1_23 // J8-3 + #define Y_SERIAL_RX_PIN P1_23 // J8-3 + #define Z_SERIAL_TX_PIN P2_12 // J8-4 + #define Z_SERIAL_RX_PIN P2_12 // J8-4 + #define E0_SERIAL_TX_PIN P2_11 // J8-5 + #define E0_SERIAL_RX_PIN P2_11 // J8-5 + #define E1_SERIAL_TX_PIN P4_28 // J8-6 + #define E1_SERIAL_RX_PIN P4_28 // J8-6 // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 From 2d758663db570d8fc37255bf75c1bd3a98c333fe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 03:25:35 -0500 Subject: [PATCH 0334/1454] G12 E soft endstops parameter (#17788) --- Marlin/src/gcode/calibrate/G425.cpp | 2 -- Marlin/src/gcode/feature/clean/G12.cpp | 13 +++++++++---- Marlin/src/libs/nozzle.cpp | 22 ++++++++++++---------- Marlin/src/module/motion.h | 2 ++ 4 files changed, 23 insertions(+), 16 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 18b5dc56ab..b0126c44da 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -92,8 +92,6 @@ struct measurements_t { xy_float_t nozzle_outer_dimension = nod; }; -#define TEMPORARY_SOFT_ENDSTOP_STATE(enable) REMEMBER(tes, soft_endstops_enabled, enable); - #if ENABLED(BACKLASH_GCODE) #define TEMPORARY_BACKLASH_CORRECTION(value) REMEMBER(tbst, backlash.correction, value) #else diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index 6d13a010be..bdfaf38a06 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -37,6 +37,11 @@ /** * G12: Clean the nozzle + * + * E : 0=Never or 1=Always apply the "software endstop" limits + * P0 S : Stroke cleaning with S strokes + * P1 Sn T : Zigzag cleaning with S repeats and T zigzags + * P2 Sn R : Circle cleaning with S repeats and R radius */ void GcodeSuite::G12() { // Don't allow nozzle cleaning without homing first @@ -45,14 +50,12 @@ void GcodeSuite::G12() { const uint8_t pattern = parser.ushortval('P', 0), strokes = parser.ushortval('S', NOZZLE_CLEAN_STROKES), objects = parser.ushortval('T', NOZZLE_CLEAN_TRIANGLES); - const float radius = parser.floatval('R', NOZZLE_CLEAN_CIRCLE_RADIUS); + const float radius = parser.linearval('R', NOZZLE_CLEAN_CIRCLE_RADIUS); const bool seenxyz = parser.seen("XYZ"); const uint8_t cleans = (!seenxyz || parser.boolval('X') ? _BV(X_AXIS) : 0) | (!seenxyz || parser.boolval('Y') ? _BV(Y_AXIS) : 0) - #if DISABLED(NOZZLE_CLEAN_NO_Z) - | (!seenxyz || parser.boolval('Z') ? _BV(Z_AXIS) : 0) - #endif + | TERN(NOZZLE_CLEAN_NO_Z, 0, (!seenxyz || parser.boolval('Z') ? _BV(Z_AXIS) : 0)) ; #if HAS_LEVELING @@ -60,6 +63,8 @@ void GcodeSuite::G12() { TEMPORARY_BED_LEVELING_STATE(!TEST(cleans, Z_AXIS) && planner.leveling_active); #endif + TEMPORARY_SOFT_ENDSTOP_STATE(parser.boolval('E')); + nozzle.clean(pattern, strokes, radius, objects, cleans); } diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index f3434a642d..6796b4d112 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -152,18 +152,20 @@ Nozzle nozzle; LIMIT( end[arrPos].A, soft_endstop.min.A, soft_endstop.max.A); \ }while(0) - LIMIT_AXIS(x); - LIMIT_AXIS(y); - LIMIT_AXIS(z); + if (soft_endstops_enabled) { - const bool radiusOutOfRange = (middle[arrPos].x + radius > soft_endstop.max.x) - || (middle[arrPos].x - radius < soft_endstop.min.x) - || (middle[arrPos].y + radius > soft_endstop.max.y) - || (middle[arrPos].y - radius < soft_endstop.min.y); + LIMIT_AXIS(x); + LIMIT_AXIS(y); + LIMIT_AXIS(z); + const bool radiusOutOfRange = (middle[arrPos].x + radius > soft_endstop.max.x) + || (middle[arrPos].x - radius < soft_endstop.min.x) + || (middle[arrPos].y + radius > soft_endstop.max.y) + || (middle[arrPos].y - radius < soft_endstop.min.y); + if (radiusOutOfRange && pattern == 2) { + SERIAL_ECHOLNPGM("Warning: Radius Out of Range"); + return; + } - if (radiusOutOfRange && pattern == 2) { - SERIAL_ECHOLNPGM("Warning: Radius Out of Range"); - return; } #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index eb7bc37894..1348adb3bd 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -152,6 +152,7 @@ typedef struct { xyz_pos_t min, max; } axis_limits_t; , const uint8_t old_tool_index=0, const uint8_t new_tool_index=0 #endif ); + #define TEMPORARY_SOFT_ENDSTOP_STATE(enable) REMEMBER(tes, soft_endstops_enabled, enable); #else constexpr bool soft_endstops_enabled = false; //constexpr axis_limits_t soft_endstop = { @@ -159,6 +160,7 @@ typedef struct { xyz_pos_t min, max; } axis_limits_t; // { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } }; #define apply_motion_limits(V) NOOP #define update_software_endstops(...) NOOP + #define TEMPORARY_SOFT_ENDSTOP_STATE(...) NOOP #endif void report_real_position(); From 5e6faa999d1e1e7ce7dfd51943e1259e56399115 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 14:46:33 -0500 Subject: [PATCH 0335/1454] Refine EEPROM types / flags (#17772) --- Marlin/src/HAL/AVR/eeprom.cpp | 5 +- Marlin/src/HAL/DUE/HAL.h | 9 +-- .../HAL/DUE/{eeprom.cpp => eeprom_flash.cpp} | 17 +++-- ...epromEmulation.cpp => eeprom_if_flash.cpp} | 1 + Marlin/src/HAL/DUE/eeprom_wired.cpp | 69 +++++++++++++++++++ Marlin/src/HAL/DUE/inc/Conditionals_post.h | 4 +- Marlin/src/HAL/ESP32/HAL.h | 6 -- Marlin/src/HAL/ESP32/eeprom.cpp | 4 +- Marlin/src/HAL/ESP32/inc/Conditionals_post.h | 5 -- Marlin/src/HAL/LINUX/arduino.cpp | 14 ---- Marlin/src/HAL/LINUX/include/Arduino.h | 6 -- Marlin/src/HAL/LPC1768/eeprom_flash.cpp | 4 +- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 4 +- Marlin/src/HAL/LPC1768/eeprom_wired.cpp | 7 +- .../src/HAL/LPC1768/inc/Conditionals_post.h | 2 - Marlin/src/HAL/SAMD51/HAL.h | 6 -- .../SAMD51/{eeprom.cpp => eeprom_wired.cpp} | 11 ++- Marlin/src/HAL/SAMD51/inc/Conditionals_post.h | 2 + Marlin/src/HAL/STM32/HAL.h | 10 --- Marlin/src/HAL/STM32/eeprom_flash.cpp | 20 ++---- Marlin/src/HAL/STM32/eeprom_sram.cpp | 64 +++++++++++++++++ Marlin/src/HAL/STM32/eeprom_wired.cpp | 43 ++++-------- Marlin/src/HAL/STM32/inc/Conditionals_post.h | 2 + Marlin/src/HAL/STM32F1/HAL.h | 13 ---- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 5 +- .../src/HAL/STM32F1/inc/Conditionals_post.h | 2 + Marlin/src/HAL/STM32_F4_F7/HAL.h | 19 ++--- Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp | 7 +- Marlin/src/HAL/STM32_F4_F7/eeprom.cpp | 8 +-- Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp | 7 +- ...EmulatedEeprom.cpp => eeprom_if_flash.cpp} | 5 +- Marlin/src/HAL/TEENSY35_36/eeprom.cpp | 5 +- Marlin/src/HAL/shared/eeprom_if.h | 30 ++++++++ .../{eeprom_i2c.cpp => eeprom_if_i2c.cpp} | 13 ++-- .../{eeprom_spi.cpp => eeprom_if_spi.cpp} | 9 +-- Marlin/src/inc/Conditionals_adv.h | 5 ++ Marlin/src/inc/SanityCheck.h | 8 ++- Marlin/src/module/printcounter.h | 10 +-- Marlin/src/pins/stm32f0/pins_MALYAN_M300.h | 4 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 12 ++-- .../src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 12 ++-- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 10 +-- Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h | 12 ++-- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 12 ++-- Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 6 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 6 +- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 6 +- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 6 +- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 2 + Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 6 +- Marlin/src/pins/stm32f1/pins_MALYAN_M200.h | 8 +-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 12 ++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 6 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 6 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 10 ++- .../src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 6 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 14 ++-- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 4 +- 58 files changed, 365 insertions(+), 256 deletions(-) rename Marlin/src/HAL/DUE/{eeprom.cpp => eeprom_flash.cpp} (87%) rename Marlin/src/HAL/DUE/{EepromEmulation.cpp => eeprom_if_flash.cpp} (99%) create mode 100644 Marlin/src/HAL/DUE/eeprom_wired.cpp rename Marlin/src/HAL/SAMD51/{eeprom.cpp => eeprom_wired.cpp} (87%) create mode 100644 Marlin/src/HAL/STM32/eeprom_sram.cpp rename Marlin/src/HAL/STM32_F4_F7/{EmulatedEeprom.cpp => eeprom_if_flash.cpp} (97%) create mode 100644 Marlin/src/HAL/shared/eeprom_if.h rename Marlin/src/HAL/shared/{eeprom_i2c.cpp => eeprom_if_i2c.cpp} (93%) rename Marlin/src/HAL/shared/{eeprom_spi.cpp => eeprom_if_spi.cpp} (93%) diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index ee416b7a12..e946668054 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -27,7 +27,8 @@ #include "../shared/eeprom_api.h" -bool PersistentStore::access_start() { return true; } +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { @@ -61,7 +62,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; // always assume success for AVR's } -size_t PersistentStore::capacity() { return E2END + 1; } - #endif // EEPROM_SETTINGS || SD_FIRMWARE_UPDATE #endif // __AVR__ diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 42f6f175fb..0624c5b401 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -30,6 +30,7 @@ #define CPU_32_BIT #include "../shared/Marduino.h" +#include "../shared/eeprom_if.h" #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" @@ -130,14 +131,6 @@ void sei(); // Enable interrupts void HAL_clear_reset_source(); // clear reset reason uint8_t HAL_get_reset_source(); // get reset reason -// -// EEPROM -// -void eeprom_write_byte(uint8_t *pos, unsigned char value); -uint8_t eeprom_read_byte(uint8_t *pos); -void eeprom_read_block (void *__dst, const void *__src, size_t __n); -void eeprom_update_block (const void *__src, void *__dst, size_t __n); - // // ADC // diff --git a/Marlin/src/HAL/DUE/eeprom.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp similarity index 87% rename from Marlin/src/HAL/DUE/eeprom.cpp rename to Marlin/src/HAL/DUE/eeprom_flash.cpp index ec9ef51ffc..7076dd03db 100644 --- a/Marlin/src/HAL/DUE/eeprom.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -22,25 +22,26 @@ */ #ifdef ARDUINO_ARCH_SAM -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) +#if ENABLED(FLASH_EEPROM_EMULATION) #include "../../inc/MarlinConfig.h" + +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -#if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION) +#if !defined(E2END) #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) #endif extern void eeprom_flush(); -bool PersistentStore::access_start() { return true; } +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { - #if ENABLED(FLASH_EEPROM_EMULATION) - eeprom_flush(); - #endif + eeprom_flush(); return true; } @@ -76,7 +77,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { return E2END + 1; } - #endif // EEPROM_SETTINGS #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/EepromEmulation.cpp b/Marlin/src/HAL/DUE/eeprom_if_flash.cpp similarity index 99% rename from Marlin/src/HAL/DUE/EepromEmulation.cpp rename to Marlin/src/HAL/DUE/eeprom_if_flash.cpp index 8be9affa68..8464ed62bb 100644 --- a/Marlin/src/HAL/DUE/EepromEmulation.cpp +++ b/Marlin/src/HAL/DUE/eeprom_if_flash.cpp @@ -57,6 +57,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/Marduino.h" +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" #define EEPROMSize 4096 diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp new file mode 100644 index 0000000000..429d8df374 --- /dev/null +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef ARDUINO_ARCH_SAM + +#include "../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" + +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t * const p = (uint8_t * const)pos; + uint8_t v = *value; + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + }; + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + uint8_t c = eeprom_read_byte((uint8_t*)pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h index 8a305009ce..9b76c25102 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -22,7 +22,7 @@ #pragma once #if USE_FALLBACK_EEPROM - #undef SRAM_EEPROM_EMULATION - #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION +#elif EITHER(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index a04343b69e..4b1ccbf20f 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -109,12 +109,6 @@ int freeMemory(); void analogWrite(pin_t pin, int value); -// EEPROM -void eeprom_write_byte(uint8_t *pos, unsigned char value); -uint8_t eeprom_read_byte(uint8_t *pos); -void eeprom_read_block (void *__dst, const void *__src, size_t __n); -void eeprom_update_block (const void *__src, void *__dst, size_t __n); - // ADC #define HAL_ANALOG_SELECT(pin) diff --git a/Marlin/src/HAL/ESP32/eeprom.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp index 8b75dc51e8..35cebb592f 100644 --- a/Marlin/src/HAL/ESP32/eeprom.cpp +++ b/Marlin/src/HAL/ESP32/eeprom.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfig.h" -#if USE_WIRED_EEPROM +#if ENABLED(EEPROM_SETTINGS) #include "../shared/eeprom_api.h" #include @@ -58,5 +58,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return EEPROM_SIZE; } -#endif // USE_WIRED_EEPROM +#endif // EEPROM_SETTINGS #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h index 8849c06e93..0285c52ee3 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h @@ -20,8 +20,3 @@ * */ #pragma once - -#undef USE_WIRED_EEPROM -#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) - #define USE_WIRED_EEPROM 1 -#endif diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index d9fa84ac7c..122a1a4a18 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -75,20 +75,6 @@ uint16_t analogRead(pin_t adc_pin) { return Gpio::get(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin)); } -// ************************** -// Persistent Config Storage -// ************************** - -void eeprom_write_byte(unsigned char *pos, unsigned char value) { - -} - -unsigned char eeprom_read_byte(uint8_t * pos) { return '\0'; } - -void eeprom_read_block(void *__dst, const void *__src, size_t __n) { } - -void eeprom_update_block(const void *__src, void *__dst, size_t __n) { } - char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) { char format_string[20]; snprintf(format_string, 20, "%%%d.%df", __width, __prec); diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index 55bf0f95ee..928f551fb4 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -106,12 +106,6 @@ bool digitalRead(pin_t); void analogWrite(pin_t, int); uint16_t analogRead(pin_t); -// EEPROM -void eeprom_write_byte(unsigned char *pos, unsigned char value); -unsigned char eeprom_read_byte(unsigned char *pos); -void eeprom_read_block(void *__dst, const void *__src, size_t __n); -void eeprom_update_block(const void *__src, void *__dst, size_t __n); - int32_t random(int32_t); int32_t random(int32_t, int32_t); void randomSeed(uint32_t); diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp index ea4ef7c66c..3bcda68adb 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp @@ -58,6 +58,8 @@ static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; static int current_slot = 0; +size_t PersistentStore::capacity() { return EEPROM_SIZE; } + bool PersistentStore::access_start() { uint32_t first_nblank_loc, first_nblank_val; IAP_STATUS_CODE status; @@ -122,7 +124,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; // return true for any error } -size_t PersistentStore::capacity() { return EEPROM_SIZE; } - #endif // FLASH_EEPROM_EMULATION #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index ce76a5a439..aac41ab307 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -38,6 +38,8 @@ FATFS fat_fs; FIL eeprom_file; bool eeprom_file_open = false; +size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM + bool PersistentStore::access_start() { const char eeprom_erase_value = 0xFF; MSC_Aquire_Lock(); @@ -168,7 +170,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin return bytes_read != size; // return true for any error } -size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM - #endif // SDCARD_EEPROM_EMULATION #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index 3395601a24..f5db53434d 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -19,19 +19,14 @@ * along with this program. If not, see . * */ - -/** - * I2C/SPI EEPROM interface for LPC1768 - */ - #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -#include #ifndef EEPROM_SIZE #define EEPROM_SIZE 0x8000 // 32kB‬ diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index 25c3b79cd1..24ff12cf19 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -21,8 +21,6 @@ */ #pragma once -#undef I2C_EEPROM // Arduino framework provides code for I2C - #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index f2ee02a22f..322489e193 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -113,12 +113,6 @@ typedef int8_t pin_t; void HAL_clear_reset_source(); // clear reset reason uint8_t HAL_get_reset_source(); // get reset reason -// -// EEPROM -// -void eeprom_write_byte(uint8_t *pos, unsigned char value); -uint8_t eeprom_read_byte(uint8_t *pos); - // // ADC // diff --git a/Marlin/src/HAL/SAMD51/eeprom.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp similarity index 87% rename from Marlin/src/HAL/SAMD51/eeprom.cpp rename to Marlin/src/HAL/SAMD51/eeprom_wired.cpp index e167515bff..9dc83f37e6 100644 --- a/Marlin/src/HAL/SAMD51/eeprom.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp @@ -18,18 +18,17 @@ * along with this program. If not, see . * */ - #ifdef __SAMD51__ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && NONE(QSPI_EEPROM, FLASH_EEPROM_EMULATION) +#if USE_WIRED_EEPROM +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } - -bool PersistentStore::access_start() { return true; } +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { @@ -62,5 +61,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -#endif // EEPROM_SETTINGS && !(QSPI_EEPROM || FLASH_EEPROM_EMULATION) +#endif // USE_WIRED_EEPROM #endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index 24ff12cf19..9b76c25102 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -23,4 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION +#elif EITHER(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index c310cca74e..4c64d95153 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -191,16 +191,6 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// -// EEPROM -// - -// Wire library should work for i2c EEPROMs -void eeprom_write_byte(uint8_t *pos, unsigned char value); -uint8_t eeprom_read_byte(uint8_t *pos); -void eeprom_read_block(void *__dst, const void *__src, size_t __n); -void eeprom_update_block(const void *__src, void *__dst, size_t __n); - // // ADC // diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 765e847420..49862957e8 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION) +#if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/eeprom_api.h" @@ -235,13 +235,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - const uint8_t c = ( - #if ENABLED(FLASH_EEPROM_LEVELING) - ram_eeprom[pos] - #else - eeprom_buffered_read_byte(pos) - #endif - ); + const uint8_t c = TERN(FLASH_EEPROM_LEVELING, ram_eeprom[pos], eeprom_buffered_read_byte(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; @@ -251,14 +245,8 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t } size_t PersistentStore::capacity() { - return ( - #if ENABLED(FLASH_EEPROM_LEVELING) - EEPROM_SIZE - #else - E2END + 1 - #endif - ); + return TERN(FLASH_EEPROM_LEVELING, EEPROM_SIZE, E2END + 1); } -#endif // EEPROM_SETTINGS && FLASH_EEPROM_EMULATION +#endif // FLASH_EEPROM_EMULATION #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp new file mode 100644 index 0000000000..0993dee33d --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -0,0 +1,64 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SRAM_EEPROM_EMULATION) + +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" + +size_t PersistentStore::capacity() { return 4096; } // 4K of SRAM +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t v = *value; + + // Save to Backup SRAM + *(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v; + + crc16(crc, &v, 1); + pos++; + value++; + }; + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + // Read from either external EEPROM, program flash or Backup SRAM + const uint8_t c = ( *(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)) ); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // SRAM_EEPROM_EMULATION +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index b83a2eb2bb..465cf44a25 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -24,10 +24,13 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(USE_WIRED_EEPROM, SRAM_EEPROM_EMULATION) +#if USE_WIRED_EEPROM + +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" +size_t PersistentStore::capacity() { return E2END + 1; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } @@ -35,21 +38,16 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui while (size--) { uint8_t v = *value; - // Save to either external EEPROM, program flash or Backup SRAM - #if USE_WIRED_EEPROM - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - uint8_t * const p = (uint8_t * const)pos; - if (v != eeprom_read_byte(p)) { - eeprom_write_byte(p, v); - if (eeprom_read_byte(p) != v) { - SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); - return true; - } + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; } - #else - *(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v; - #endif + } crc16(crc, &v, 1); pos++; @@ -62,14 +60,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { // Read from either external EEPROM, program flash or Backup SRAM - const uint8_t c = ( - #if USE_WIRED_EEPROM - eeprom_read_byte((uint8_t*)pos) - #else - (*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos))) - #endif - ); - + const uint8_t c = eeprom_read_byte((uint8_t*)pos); if (writing) *value = c; crc16(crc, &c, 1); pos++; @@ -78,9 +69,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { - return TERN(USE_WIRED_EEPROM, E2END + 1, 4096); // 4K for emulated -} - -#endif // USE_WIRED_EEPROM || SRAM_EEPROM_EMULATION +#endif // USE_WIRED_EEPROM #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index 27e814a0a6..efe4d72a6f 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -24,4 +24,6 @@ // If no real or emulated EEPROM selected, fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION +#elif EITHER(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 629e455871..c69d62e125 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -248,19 +248,6 @@ static int freeMemory() { #pragma GCC diagnostic pop -// -// EEPROM -// - -/** - * TODO: Write all this EEPROM stuff. Can emulate EEPROM in flash as last resort. - * Wire library should work for i2c EEPROMs. - */ -void eeprom_write_byte(uint8_t *pos, unsigned char value); -uint8_t eeprom_read_byte(uint8_t *pos); -void eeprom_read_block(void *__dst, const void *__src, size_t __n); -void eeprom_update_block(const void *__src, void *__dst, size_t __n); - // // ADC // diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index 8527f175a6..e53e9d8674 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -23,8 +23,11 @@ #if USE_WIRED_EEPROM +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" +size_t PersistentStore::capacity() { return E2END + 1; } + bool PersistentStore::access_start() { #if ENABLED(SPI_EEPROM) #if SPI_CHAN_EEPROM1 == 1 @@ -70,7 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { return E2END + 1; } - #endif // USE_WIRED_EEPROM #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h index 32ad3a57b9..be011af35e 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h @@ -24,4 +24,6 @@ // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION +#elif EITHER(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h index b5d8ac29cf..37bb5552ab 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.h +++ b/Marlin/src/HAL/STM32_F4_F7/HAL.h @@ -51,6 +51,8 @@ #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." #elif SERIAL_PORT == -1 #define MYSERIAL0 SerialUSB +#elif SERIAL_PORT == 0 + #define MYSERIAL0 Serial1 #elif SERIAL_PORT == 1 #define MYSERIAL0 SerialUART1 #elif SERIAL_PORT == 2 @@ -74,6 +76,8 @@ #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." #elif SERIAL_PORT_2 == -1 #define MYSERIAL1 SerialUSB + #elif SERIAL_PORT_2 == 0 + #define MYSERIAL1 Serial1 #elif SERIAL_PORT_2 == 1 #define MYSERIAL1 SerialUART1 #elif SERIAL_PORT_2 == 2 @@ -103,6 +107,8 @@ #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." #elif DGUS_SERIAL_PORT == -1 #define DGUS_SERIAL SerialUSB + #elif DGUS_SERIAL_PORT == 0 + #define DGUS_SERIAL Serial1 #elif DGUS_SERIAL_PORT == 1 #define DGUS_SERIAL SerialUART1 #elif DGUS_SERIAL_PORT == 2 @@ -206,19 +212,6 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// -// EEPROM -// - -/** - * TODO: Write all this EEPROM stuff. Can emulate EEPROM in flash as last resort. - * Wire library should work for i2c EEPROMs. - */ -void eeprom_write_byte(uint8_t *pos, unsigned char value); -uint8_t eeprom_read_byte(uint8_t *pos); -void eeprom_read_block (void *__dst, const void *__src, size_t __n); -void eeprom_update_block (const void *__src, void *__dst, size_t __n); - // // ADC // diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp index deb14f2cfe..673ab3372b 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp @@ -20,6 +20,7 @@ * along with this program. If not, see . * */ +#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) /** * Software SPI functions originally from Arduino Sd2Card Library @@ -30,8 +31,6 @@ * Adapted to the Marlin STM32F4/7 HAL */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - #include "../../inc/MarlinConfig.h" #include @@ -121,7 +120,7 @@ uint8_t spiRec() { */ void spiRead(uint8_t* buf, uint16_t nbyte) { SPI.beginTransaction(spiConfig); - #ifdef STM32GENERIC + #ifndef STM32GENERIC SPI.dmaTransfer(0, const_cast(buf), nbyte); #else SPI.transfer((uint8_t*)buf, nbyte); @@ -153,7 +152,7 @@ void spiSend(uint8_t b) { void spiSendBlock(uint8_t token, const uint8_t* buf) { SPI.beginTransaction(spiConfig); SPI.transfer(token); - #ifdef STM32GENERIC + #ifndef STM32GENERIC SPI.dmaSend(const_cast(buf), 512); #else SPI.transfer((uint8_t*)buf, nullptr, 512); diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp index 0b0aa4475e..370d2885ae 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp @@ -22,13 +22,15 @@ */ #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #if ENABLED(EEPROM_SETTINGS) +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -bool PersistentStore::access_start() { return true; } +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { @@ -62,7 +64,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { return E2END + 1; } - #endif // EEPROM_SETTINGS #endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp index 3358fa3df7..cb4811d2aa 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp @@ -1,6 +1,6 @@ /** ****************************************************************************** - * @file EEPROM/EEPROM_Emulation/src/eeprom.c + * @file eeprom_emul.cpp * @author MCD Application Team * @version V1.2.6 * @date 04-November-2016 @@ -49,6 +49,10 @@ */ #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(FLASH_EEPROM_EMULATION) + /* Includes ------------------------------------------------------------------*/ #include "eeprom_emul.h" @@ -518,6 +522,7 @@ static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) { return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE); } +#endif // FLASH_EEPROM_EMULATION #endif // STM32GENERIC && (STM32F4 || STM32F7) /** diff --git a/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_if_flash.cpp similarity index 97% rename from Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp rename to Marlin/src/HAL/STM32_F4_F7/eeprom_if_flash.cpp index 3249ef2b7c..86b80f2b8b 100644 --- a/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_if_flash.cpp @@ -16,12 +16,10 @@ * along with this program. If not, see . * */ - #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) /** - * Description: Functions for a Flash emulated EEPROM - * Not platform dependent. + * Arduino-style interface for Flash emulated EEPROM */ // Include configs and pins to get all EEPROM flags @@ -35,6 +33,7 @@ #include "HAL.h" #include "eeprom_emul.h" +#include "../shared/eeprom_if.h" // ------------------------ // Local defines diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index bd597c2ded..ff8fa3626d 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -29,7 +29,8 @@ #include "../shared/eeprom_api.h" #include -bool PersistentStore::access_start() { return true; } +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { @@ -63,7 +64,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { return E2END + 1; } - #endif // USE_WIRED_EEPROM #endif // __MK64FX512__ || __MK66FX1M0__ diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h new file mode 100644 index 0000000000..e6e7046011 --- /dev/null +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// +// EEPROM +// +void eeprom_write_byte(uint8_t *pos, unsigned char value); +uint8_t eeprom_read_byte(uint8_t *pos); +void eeprom_read_block(void *__dst, const void *__src, size_t __n); +void eeprom_update_block(const void *__src, void *__dst, size_t __n); diff --git a/Marlin/src/HAL/shared/eeprom_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp similarity index 93% rename from Marlin/src/HAL/shared/eeprom_i2c.cpp rename to Marlin/src/HAL/shared/eeprom_if_i2c.cpp index cc60c8d196..a4ad9763ba 100644 --- a/Marlin/src/HAL/shared/eeprom_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -21,20 +21,19 @@ */ /** - * Description: functions for I2C connected external EEPROM. - * Not platform dependent. - * - * TODO: Some platform Arduino libraries define these functions - * so Marlin needs to add a glue layer to prevent the conflict. + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. */ #include "../../inc/MarlinConfig.h" -#if ENABLED(I2C_EEPROM) +#if BOTH(USE_SHARED_EEPROM, I2C_EEPROM) #include "../HAL.h" #include +#include "eeprom_if.h" + #ifndef EEPROM_WRITE_DELAY #define EEPROM_WRITE_DELAY 5 #endif @@ -126,4 +125,4 @@ void eeprom_read_block(void* pos, const void *__dst, size_t n) { if (Wire.available()) *((uint8_t*)pos + c) = Wire.read(); } -#endif // I2C_EEPROM +#endif // USE_SHARED_EEPROM && I2C_EEPROM diff --git a/Marlin/src/HAL/shared/eeprom_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp similarity index 93% rename from Marlin/src/HAL/shared/eeprom_spi.cpp rename to Marlin/src/HAL/shared/eeprom_if_spi.cpp index 73602feaaf..4c3a92e020 100644 --- a/Marlin/src/HAL/shared/eeprom_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp @@ -21,15 +21,16 @@ */ /** - * Description: functions for SPI connected external EEPROM. - * Not platform dependent. + * Platform-independent Arduino functions for SPI EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. */ #include "../../inc/MarlinConfig.h" -#if ENABLED(SPI_EEPROM) +#if BOTH(USE_SHARED_EEPROM, SPI_EEPROM) #include "../HAL.h" +#include "eeprom_if.h" #define CMD_WREN 6 // WREN #define CMD_READ 2 // WRITE @@ -119,4 +120,4 @@ void eeprom_update_block(const void* src, void* eeprom_address, size_t n) { delay(EEPROM_WRITE_DELAY); // wait for page write to complete } -#endif // SPI_EEPROM +#endif // USE_SHARED_EEPROM && I2C_EEPROM diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 9a2b9f2a0b..2dd9f95d81 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -337,3 +337,8 @@ #else #define SD_CONNECTION_IS(...) 0 #endif + +// Flag if an EEPROM type is pre-selected +#if ENABLED(EEPROM_SETTINGS) && NONE(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define NO_EEPROM_SELECTED 1 +#endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 03701c7cc3..c420740125 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2054,8 +2054,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * Make sure only one EEPROM type is enabled */ -#if ENABLED(EEPROM_SETTINGS) && 1 < ENABLED(SDCARD_EEPROM_EMULATION) + ENABLED(FLASH_EEPROM_EMULATION) + ENABLED(SRAM_EEPROM_EMULATION) - #error "Please select only one of SDCARD, FLASH, or SRAM_EEPROM_EMULATION." +#if ENABLED(EEPROM_SETTINGS) + #if 1 < 0 \ + + ENABLED(I2C_EEPROM) + ENABLED(SPI_EEPROM) + ENABLED(QSPI_EEPROM) \ + + ENABLED(SDCARD_EEPROM_EMULATION) + ENABLED(FLASH_EEPROM_EMULATION) + ENABLED(SRAM_EEPROM_EMULATION) + #error "Please select only one method of EEPROM Persistent Storage." + #endif #endif /** diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 39a237cc44..bb4cf3c795 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -28,12 +28,8 @@ // Print debug messages with M111 S2 //#define DEBUG_PRINTCOUNTER -#if USE_WIRED_EEPROM - // round up address to next page boundary (assuming 32 byte pages) - #define STATS_EEPROM_ADDRESS 0x40 -#else - #define STATS_EEPROM_ADDRESS 0x32 -#endif +// Round up I2C / SPI address to next page boundary (assuming 32 byte pages) +#define STATS_EEPROM_ADDRESS TERN(USE_WIRED_EEPROM, 0x40, 0x32) struct printStatistics { // 16 bytes //const uint8_t magic; // Magic header, it will always be 0x16 @@ -57,7 +53,7 @@ class PrintCounter: public Stopwatch { private: typedef Stopwatch super; - #if USE_WIRED_EEPROM || defined(CPU_32_BIT) + #if EITHER(USE_WIRED_EEPROM, CPU_32_BIT) typedef uint32_t eeprom_address_t; #else typedef uint16_t eeprom_address_t; diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index c9c87d49b9..129a3175bd 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -31,7 +31,9 @@ // // EEPROM Emulation // -#define FLASH_EEPROM_EMULATION +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION +#endif // // SD CARD SPI diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index ea5fdaa6da..d7c677e3ff 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -33,11 +33,13 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE (0x800U) // 2KB -#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) -#undef E2END -#define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #undef E2END + #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#endif // // Servos diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 6658f1fd8f..a8c295c134 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -31,11 +31,13 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE (0x800U) // 2KB -#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) -#undef E2END -#define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #undef E2END + #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#endif // // Servos diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 39c70f0417..6d42b83957 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -33,10 +33,12 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE (0x800U) // 2KB -#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) -#define E2END (EEPROM_PAGE_SIZE - 1) +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define E2END (EEPROM_PAGE_SIZE - 1) +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index ab6757d682..b40306e22d 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -38,11 +38,13 @@ // // Flash EEPROM Emulation // -#define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE (0x800U) // 2KB -#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) -#undef E2END -#define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #undef E2END + #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index b2cdd1c5db..63377f8e16 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -35,11 +35,13 @@ #define DISABLE_JTAG -#define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE (0x800U) // 2KB -#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) -#undef E2END -#define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #undef E2END + #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB +#endif // // Servos diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 3fd0b5ae46..908a100341 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -52,8 +52,10 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define E2END 0xFFF // 4KB +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 9a12cfd7b0..ca1c2894cb 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -52,8 +52,10 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define E2END 0xFFF // 4KB +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 3fd0b5ae46..908a100341 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -52,8 +52,10 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define E2END 0xFFF // 4KB +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index f885db7fed..8d7687f520 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -52,8 +52,10 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#define FLASH_EEPROM_EMULATION -#define E2END 0xFFF // 4KB +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define E2END 0xFFF // 4KB +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 0a4382894f..340e405302 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -44,9 +44,11 @@ //#define I2C_EEPROM // AT24C64 //#define E2END 0x7FFFUL // 64KB + //#define FLASH_EEPROM_EMULATION //#define E2END 0xFFFUL // 4KB //#define E2END (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL - 1UL) + //#define EEPROM_CHITCHAT //#define DEBUG_EEPROM_READWRITE diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 50ac8c94be..8f5619aa69 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -147,8 +147,10 @@ // Persistent Storage // If no option is selected below the SD Card will be used // -//#define SPI_EEPROM -#define FLASH_EEPROM_EMULATION +#if NO_EEPROM_SELECTED + //#define SPI_EEPROM + #define FLASH_EEPROM_EMULATION +#endif #undef E2END #if ENABLED(SPI_EEPROM) diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 9829018d8d..00dd2e1184 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -31,10 +31,10 @@ #define BOARD_INFO_NAME "Malyan M200" -// Enable EEPROM Emulation for this board -// This setting should probably be in configuration.h -// but it is literally the only board which uses it. -#define FLASH_EEPROM_EMULATION +// Assume Flash EEPROM +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION +#endif #define SDSS SS_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index ff210c4cff..6f3897814d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -38,11 +38,13 @@ // #define DISABLE_DEBUG -#define FLASH_EEPROM_EMULATION -// 2K in a AT24C16N -#define EEPROM_PAGE_SIZE (0x800U) // 2KB -#define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) -#define E2END (EEPROM_PAGE_SIZE - 1) +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + // 2K in a AT24C16N + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define E2END (EEPROM_PAGE_SIZE - 1) +#endif // // Note: MKS Robin mini board is using SPI2 interface. diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 5a4ac26617..06369fbd27 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -41,8 +41,10 @@ // // EEPROM // -//#define FLASH_EEPROM_EMULATION -#define SDCARD_EEPROM_EMULATION +#if NO_EEPROM_SELECTED + //#define FLASH_EEPROM_EMULATION + #define SDCARD_EEPROM_EMULATION +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index ee5c4da1fe..838a5e9447 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -30,8 +30,10 @@ #define BOARD_INFO_NAME "BIGTREE Btt002 1.0" // Use one of these or SDCard-based Emulation will be used -//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#if NO_EEPROM_SELECTED + //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation + #define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#endif // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index ac8b731aae..a61ef1afaf 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -32,9 +32,11 @@ #define BOARD_INFO_NAME "BIGTREE GTR 1.0" // Use one of these or SDCard-based Emulation will be used -//#define I2C_EEPROM -//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#if NO_EEPROM_SELECTED + //#define I2C_EEPROM + //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation + //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#endif #define TP // Enable to define servo and probe pins @@ -389,3 +391,5 @@ //#define DOGLCD_MOSI PB15 #endif // HAS_SPI_LCD + +#undef TP diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 02f2c9071b..8d68ca3f9f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -30,8 +30,10 @@ #define BOARD_INFO_NAME "BIGTREE SKR Pro 1.1" // redefined? // Use one of these or SDCard-based Emulation will be used -//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation -#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#if NO_EEPROM_SELECTED + //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation + #define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#endif // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index bdadbe36c2..e3f02bb73a 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -34,19 +34,21 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #endif -// change the prio to 3 , 2 is for software serial +// Change the priority to 3. Priority 2 is for software serial. //#define TEMP_TIMER_IRQ_PRIO 3 // // EEPROM Emulation // -#define FLASH_EEPROM_EMULATION +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + //#define SRAM_EEPROM_EMULATION + //#define I2C_EEPROM +#endif + #if ENABLED(FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_LEVELING -#endif -//#define SRAM_EEPROM_EMULATION -//#define I2C_EEPROM -#ifdef I2C_EEPROM +#elif ENABLED(I2C_EEPROM) #undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. #define E2END 0xFFF // 4KB #endif diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index ac337092f6..3fba28161e 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -28,7 +28,9 @@ #define BOARD_INFO_NAME "RemRam v1" #define DEFAULT_MACHINE_NAME "RemRam" -#define SRAM_EEPROM_EMULATION // Emulate the EEPROM using Backup SRAM +#if NO_EEPROM_SELECTED + #define SRAM_EEPROM_EMULATION // Emulate the EEPROM using Backup SRAM +#endif #if HOTENDS > 1 || E_STEPPERS > 1 #error "RemRam supports only one hotend / E-stepper." From c26725c5a08b16cd7aefdac1e6ed7f235fb48699 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 14:52:03 -0500 Subject: [PATCH 0336/1454] L64XX can use hardStop for M17 See #17794 --- Marlin/src/module/stepper/L64xx.h | 32 +++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/Marlin/src/module/stepper/L64xx.h b/Marlin/src/module/stepper/L64xx.h index ca2358b967..989d84808f 100644 --- a/Marlin/src/module/stepper/L64xx.h +++ b/Marlin/src/module/stepper/L64xx.h @@ -45,7 +45,7 @@ #if AXIS_IS_L64XX(X) extern L64XX_CLASS(X) stepperX; #define X_ENABLE_INIT() NOOP - #define X_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperX.free()) + #define X_ENABLE_WRITE(STATE) (STATE ? stepperX.hardStop() : stepperX.free()) #define X_ENABLE_READ() (stepperX.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_X(L6474) #define X_DIR_INIT() SET_OUTPUT(X_DIR_PIN) @@ -65,7 +65,7 @@ #if AXIS_IS_L64XX(Y) extern L64XX_CLASS(Y) stepperY; #define Y_ENABLE_INIT() NOOP - #define Y_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperY.free()) + #define Y_ENABLE_WRITE(STATE) (STATE ? stepperY.hardStop() : stepperY.free()) #define Y_ENABLE_READ() (stepperY.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_Y(L6474) #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) @@ -85,7 +85,7 @@ #if AXIS_IS_L64XX(Z) extern L64XX_CLASS(Z) stepperZ; #define Z_ENABLE_INIT() NOOP - #define Z_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperZ.free()) + #define Z_ENABLE_WRITE(STATE) (STATE ? stepperZ.hardStop() : stepperZ.free()) #define Z_ENABLE_READ() (stepperZ.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_Z(L6474) #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) @@ -105,7 +105,7 @@ #if HAS_X2_ENABLE && AXIS_IS_L64XX(X2) extern L64XX_CLASS(X2) stepperX2; #define X2_ENABLE_INIT() NOOP - #define X2_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperX2.free()) + #define X2_ENABLE_WRITE(STATE) (STATE ? stepperX2.hardStop() : stepperX2.free()) #define X2_ENABLE_READ() (stepperX2.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_X2(L6474) #define X2_DIR_INIT() SET_OUTPUT(X2_DIR_PIN) @@ -126,7 +126,7 @@ #if HAS_Y2_ENABLE && AXIS_IS_L64XX(Y2) extern L64XX_CLASS(Y2) stepperY2; #define Y2_ENABLE_INIT() NOOP - #define Y2_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperY2.free()) + #define Y2_ENABLE_WRITE(STATE) (STATE ? stepperY2.hardStop() : stepperY2.free()) #define Y2_ENABLE_READ() (stepperY2.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_Y2(L6474) #define Y2_DIR_INIT() SET_OUTPUT(Y2_DIR_PIN) @@ -147,7 +147,7 @@ #if HAS_Z2_ENABLE && AXIS_IS_L64XX(Z2) extern L64XX_CLASS(Z2) stepperZ2; #define Z2_ENABLE_INIT() NOOP - #define Z2_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperZ2.free()) + #define Z2_ENABLE_WRITE(STATE) (STATE ? stepperZ2.hardStop() : stepperZ2.free()) #define Z2_ENABLE_READ() (stepperZ2.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_Z2(L6474) #define Z2_DIR_INIT() SET_OUTPUT(Z2_DIR_PIN) @@ -168,7 +168,7 @@ #if HAS_Z3_ENABLE && AXIS_IS_L64XX(Z3) extern L64XX_CLASS(Z3) stepperZ3; #define Z3_ENABLE_INIT() NOOP - #define Z3_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperZ3.free()) + #define Z3_ENABLE_WRITE(STATE) (STATE ? stepperZ3.hardStop() : stepperZ3.free()) #define Z3_ENABLE_READ() (stepperZ3.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_Z3(L6474) #define Z3_DIR_INIT() SET_OUTPUT(Z3_DIR_PIN) @@ -189,7 +189,7 @@ #if HAS_Z4_ENABLE && AXIS_IS_L64XX(Z4) extern L64XX_CLASS(Z4) stepperZ4; #define Z4_ENABLE_INIT() NOOP - #define Z4_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperZ4.free()) + #define Z4_ENABLE_WRITE(STATE) (STATE ? stepperZ4.hardStop() : stepperZ4.free()) #define Z4_ENABLE_READ() (stepperZ4.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_Z4(L6474) #define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN) @@ -210,7 +210,7 @@ #if AXIS_IS_L64XX(E0) extern L64XX_CLASS(E0) stepperE0; #define E0_ENABLE_INIT() NOOP - #define E0_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE0.free()) + #define E0_ENABLE_WRITE(STATE) (STATE ? stepperE0.hardStop() : stepperE0.free()) #define E0_ENABLE_READ() (stepperE0.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E0(L6474) #define E0_DIR_INIT() SET_OUTPUT(E0_DIR_PIN) @@ -230,7 +230,7 @@ #if AXIS_IS_L64XX(E1) extern L64XX_CLASS(E1) stepperE1; #define E1_ENABLE_INIT() NOOP - #define E1_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE1.free()) + #define E1_ENABLE_WRITE(STATE) (STATE ? stepperE1.hardStop() : stepperE1.free()) #define E1_ENABLE_READ() (stepperE1.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E1(L6474) #define E1_DIR_INIT() SET_OUTPUT(E1_DIR_PIN) @@ -250,7 +250,7 @@ #if AXIS_IS_L64XX(E2) extern L64XX_CLASS(E2) stepperE2; #define E2_ENABLE_INIT() NOOP - #define E2_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE2.free()) + #define E2_ENABLE_WRITE(STATE) (STATE ? stepperE2.hardStop() : stepperE2.free()) #define E2_ENABLE_READ() (stepperE2.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E2(L6474) #define E2_DIR_INIT() SET_OUTPUT(E2_DIR_PIN) @@ -270,7 +270,7 @@ #if AXIS_IS_L64XX(E3) extern L64XX_CLASS(E3) stepperE3; #define E3_ENABLE_INIT() NOOP - #define E3_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE3.free()) + #define E3_ENABLE_WRITE(STATE) (STATE ? stepperE3.hardStop() : stepperE3.free()) #define E3_ENABLE_READ() (stepperE3.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E3(L6474) #define E3_DIR_INIT() SET_OUTPUT(E3_DIR_PIN) @@ -287,7 +287,7 @@ #if AXIS_IS_L64XX(E4) extern L64XX_CLASS(E4) stepperE4; #define E4_ENABLE_INIT() NOOP - #define E4_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE4.free()) + #define E4_ENABLE_WRITE(STATE) (STATE ? stepperE4.hardStop() : stepperE4.free()) #define E4_ENABLE_READ() (stepperE4.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E4(L6474) #define E4_DIR_INIT() SET_OUTPUT(E4_DIR_PIN) @@ -307,7 +307,7 @@ #if AXIS_IS_L64XX(E5) extern L64XX_CLASS(E5) stepperE5; #define E5_ENABLE_INIT() NOOP - #define E5_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE5.free()) + #define E5_ENABLE_WRITE(STATE) (STATE ? stepperE5.hardStop() : stepperE5.free()) #define E5_ENABLE_READ() (stepperE5.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E5(L6474) #define E5_DIR_INIT() SET_OUTPUT(E5_DIR_PIN) @@ -327,7 +327,7 @@ #if AXIS_IS_L64XX(E6) extern L64XX_CLASS(E6) stepperE6; #define E6_ENABLE_INIT() NOOP - #define E6_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE6.free()) + #define E6_ENABLE_WRITE(STATE) (STATE ? stepperE6.hardStop() : stepperE6.free()) #define E6_ENABLE_READ() (stepperE6.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E6(L6474) #define E6_DIR_INIT() SET_OUTPUT(E6_DIR_PIN) @@ -347,7 +347,7 @@ #if AXIS_IS_L64XX(E7) extern L64XX_CLASS(E7) stepperE7; #define E7_ENABLE_INIT() NOOP - #define E7_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE7.free()) + #define E7_ENABLE_WRITE(STATE) (STATE ? stepperE7.hardStop() : stepperE7.free()) #define E7_ENABLE_READ() (stepperE7.getStatus() & STATUS_HIZ) #if AXIS_DRIVER_TYPE_E7(L6474) #define E7_DIR_INIT() SET_OUTPUT(E7_DIR_PIN) From e8b0796fc70d06f59cb217dbe11a2ad695243ad1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 14:52:42 -0500 Subject: [PATCH 0337/1454] Revert menu_item_if ahead of refactor --- Marlin/src/lcd/menu/menu.h | 15 ++------ Marlin/src/lcd/menu/menu_advanced.cpp | 43 +++++++++++------------ Marlin/src/lcd/menu/menu_bed_leveling.cpp | 8 ++--- Marlin/src/lcd/menu/menu_cancelobject.cpp | 2 +- Marlin/src/lcd/menu/menu_filament.cpp | 32 ++++++++--------- Marlin/src/lcd/menu/menu_led.cpp | 6 ++-- Marlin/src/lcd/menu/menu_main.cpp | 10 +++--- Marlin/src/lcd/menu/menu_media.cpp | 4 +-- Marlin/src/lcd/menu/menu_motion.cpp | 26 +++++++------- Marlin/src/lcd/menu/menu_temperature.cpp | 31 +++++++--------- Marlin/src/lcd/menu/menu_tune.cpp | 18 ++++------ Marlin/src/lcd/menu/menu_ubl.cpp | 4 +-- 12 files changed, 84 insertions(+), 115 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 91976cd190..fc5ff36987 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -340,8 +340,8 @@ class MenuItem_bool : public MenuEditItemBase { * menu item that exists in two screen segments is drawn and processed twice per screen * update. With each item processed 5, 10, 20, or 40 times the logic has to be simple. * - * To keep performance optimal, use the MENU_ITEM_IF/ELSE/ELIF macros. If function calls - * are needed to test conditions, they should come before START_MENU / START_SCREEN. + * To avoid repetition and side-effects, function calls for testing menu item conditions + * should be done before the menu loop (START_MENU / START_SCREEN). */ /** @@ -536,17 +536,6 @@ class MenuItem_bool : public MenuEditItemBase { #define YESNO_ITEM_N_P(N,PLABEL, V...) _CONFIRM_ITEM_N_P(N, PLABEL, ##V) #define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_P(N, GET_TEXT(LABEL), ##V) -/** - * MENU_ITEM_IF/ELSE/ELIF - * - * Apply a condition for a menu item to exist. - * When the condition passes, NEXT_ITEM updates _thisItemNr. - * This cannot be used to wrap multiple menu items. - */ -#define MENU_ITEM_IF(COND) if ((_menuLineNr == _thisItemNr) && (COND)) -#define MENU_ITEM_ELIF(COND) else if ((_menuLineNr == _thisItemNr) && (COND)) -#define MENU_ITEM_ELSE else if (_menuLineNr == _thisItemNr) - //////////////////////////////////////////// /////////////// Menu Screens /////////////// //////////////////////////////////////////// diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index e055b5c8e8..9828e7ec80 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -147,12 +147,10 @@ void menu_cancelobject(); #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) && FILAMENT_RUNOUT_DISTANCE_MM - MENU_ITEM_IF(1) { - editable.decimal = runout.runout_distance(); - EDIT_ITEM(float3, MSG_RUNOUT_DISTANCE_MM, &editable.decimal, 1, 30, - []{ runout.set_runout_distance(editable.decimal); }, true - ); - } + editable.decimal = runout.runout_distance(); + EDIT_ITEM(float3, MSG_RUNOUT_DISTANCE_MM, &editable.decimal, 1, 30, + []{ runout.set_runout_distance(editable.decimal); }, true + ); #endif END_MENU(); @@ -417,10 +415,8 @@ void menu_cancelobject(); #ifdef XY_FREQUENCY_LIMIT EDIT_ITEM(int8, MSG_XY_FREQUENCY_LIMIT, &planner.xy_freq_limit_hz, 0, 100, planner.refresh_frequency_limit, true); - MENU_ITEM_IF(1) { - editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255 * 100)); // percent to u8 - EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); - } + editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255 * 100)); // percent to u8 + EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); #endif END_MENU(); @@ -504,6 +500,10 @@ void menu_advanced_steps_per_mm() { void menu_advanced_settings() { const bool is_busy = printer_busy(); + #if ENABLED(SD_FIRMWARE_UPDATE) + bool sd_update_state = settings.sd_update_status(); + #endif + START_MENU(); BACK_ITEM(MSG_CONFIGURATION); @@ -576,19 +576,16 @@ void menu_advanced_settings() { #endif #if ENABLED(SD_FIRMWARE_UPDATE) - MENU_ITEM_IF (1) { - bool sd_update_state = settings.sd_update_status(); - EDIT_ITEM(bool, MSG_MEDIA_UPDATE, &sd_update_state, []{ - // - // Toggle the SD Firmware Update state in EEPROM - // - const bool new_state = !settings.sd_update_status(), - didset = settings.set_sd_update_status(new_state); - ui.completion_feedback(didset); - ui.return_to_status(); - if (new_state) LCD_MESSAGEPGM(MSG_RESET_PRINTER); else ui.reset_status(); - }); - } + EDIT_ITEM(bool, MSG_MEDIA_UPDATE, &sd_update_state, []{ + // + // Toggle the SD Firmware Update state in EEPROM + // + const bool new_state = !settings.sd_update_status(), + didset = settings.set_sd_update_status(new_state); + ui.completion_feedback(didset); + ui.return_to_status(); + if (new_state) LCD_MESSAGEPGM(MSG_RESET_PRINTER); else ui.reset_status(); + }); #endif #if ENABLED(EEPROM_SETTINGS) && DISABLED(SLIM_LCD_MENUS) diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 2592f26649..5192c596da 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -256,11 +256,9 @@ void menu_bed_leveling() { // Z Fade Height #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - MENU_ITEM_IF (1) { - // Shadow for editing the fade height - editable.decimal = planner.z_fade_height; - EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); - } + // Shadow for editing the fade height + editable.decimal = planner.z_fade_height; + EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); #endif // diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index 68fb1c9910..f49e478c26 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -62,7 +62,7 @@ void menu_cancelobject() { for (int8_t i = -1; i < cancelable.object_count; i++) { if (i == ao) continue; // Active is drawn on -1 index const int8_t j = i < 0 ? ao : i; // Active or index item - MENU_ITEM_IF (!cancelable.is_canceled(j)) { // Not canceled already? + if (!cancelable.is_canceled(j)) { // Not canceled already? SUBMENU_N(j, MSG_CANCEL_OBJECT_N, lcd_cancel_object_confirm); // Offer the option. if (i < 0) SKIP_ITEM(); // Extra line after active } diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index ec45eb3772..5598306ae8 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -116,16 +116,16 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { // Change filament #if E_STEPPERS == 1 PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE); - MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(active_extruder)) + if (thermalManager.targetTooColdToExtrude(active_extruder)) SUBMENU_P(msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); - MENU_ITEM_ELSE + else GCODES_ITEM_P(msg, PSTR("M600 B0")); #else PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE_E); LOOP_L_N(s, E_STEPPERS) { - MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(s)) + if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); - MENU_ITEM_ELSE { + else { ACTION_ITEM_N_P(s, msg, []{ char cmd[13]; sprintf_P(cmd, PSTR("M600 B0 T%i"), int(MenuItemBase::itemIndex)); @@ -140,16 +140,16 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { // Load filament #if E_STEPPERS == 1 PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD); - MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(active_extruder)) + if (thermalManager.targetTooColdToExtrude(active_extruder)) SUBMENU_P(msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, 0); }); - MENU_ITEM_ELSE + else GCODES_ITEM_P(msg_load, PSTR("M701")); #else PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD_E); LOOP_L_N(s, E_STEPPERS) { - MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(s)) + if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); - MENU_ITEM_ELSE { + else { ACTION_ITEM_N_P(s, msg_load, []{ char cmd[12]; sprintf_P(cmd, PSTR("M701 T%i"), int(MenuItemBase::itemIndex)); @@ -162,22 +162,22 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { // Unload filament #if E_STEPPERS == 1 PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD); - MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(active_extruder)) + if (thermalManager.targetTooColdToExtrude(active_extruder)) SUBMENU_P(msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, 0); }); - MENU_ITEM_ELSE + else GCODES_ITEM_P(msg_unload, PSTR("M702")); #else #if ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) - MENU_ITEM_IF (too_cold) + if (too_cold) SUBMENU(MSG_FILAMENTUNLOAD_ALL, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, -1); }); - MENU_ITEM_ELSE + else GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, PSTR("M702")); #endif PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD_E); LOOP_L_N(s, E_STEPPERS) { - MENU_ITEM_IF (thermalManager.targetTooColdToExtrude(s)) + if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); - MENU_ITEM_ELSE { + else { ACTION_ITEM_N_P(s, msg_unload, []{ char cmd[12]; sprintf_P(cmd, PSTR("M702 T%i"), int(MenuItemBase::itemIndex)); @@ -230,13 +230,13 @@ void menu_pause_option() { #if HAS_FILAMENT_SENSOR const bool still_out = runout.filament_ran_out; - MENU_ITEM_IF (still_out) + if (still_out) EDIT_ITEM(bool, MSG_RUNOUT_SENSOR, &runout.enabled, runout.reset); #else constexpr bool still_out = false; #endif - MENU_ITEM_IF (!still_out) + if (!still_out) ACTION_ITEM(MSG_FILAMENT_CHANGE_OPTION_RESUME, []{ pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; }); END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 62689b8a4c..ea76ae74dd 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -70,10 +70,8 @@ void menu_led_custom() { void menu_led() { START_MENU(); BACK_ITEM(MSG_MAIN); - MENU_ITEM_IF(1) { - bool led_on = leds.lights_on; - EDIT_ITEM(bool, MSG_LEDS, &led_on, leds.toggle); - } + bool led_on = leds.lights_on; + EDIT_ITEM(bool, MSG_LEDS, &led_on, leds.toggle); ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds.set_default); #if ENABLED(LED_COLOR_PRESETS) SUBMENU(MSG_LED_PRESETS, menu_led_presets); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 7e7ea71cef..f882fe6868 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -144,7 +144,7 @@ void menu_main() { #endif // !HAS_ENCODER_WHEEL && SDSUPPORT - MENU_ITEM_IF (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) + if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); SUBMENU(MSG_MOTION, menu_motion); @@ -176,9 +176,9 @@ void menu_main() { #if ENABLED(ADVANCED_PAUSE_FEATURE) #if E_STEPPERS == 1 && DISABLED(FILAMENT_LOAD_UNLOAD_GCODES) - MENU_ITEM_IF (thermalManager.targetHotEnoughToExtrude(active_extruder)) + if (thermalManager.targetHotEnoughToExtrude(active_extruder)) GCODES_ITEM(MSG_FILAMENTCHANGE, PSTR("M600 B0")); - MENU_ITEM_ELSE + else SUBMENU(MSG_FILAMENTCHANGE, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); #else SUBMENU(MSG_FILAMENTCHANGE, menu_change_filament); @@ -197,9 +197,9 @@ void menu_main() { // Switch power on/off // #if ENABLED(PSU_CONTROL) - MENU_ITEM_IF (powersupply_on) + if (powersupply_on) GCODES_ITEM(MSG_SWITCH_PS_OFF, PSTR("M81")); - MENU_ITEM_ELSE + else GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 3b3c78c1d7..7b3d1e549c 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -127,9 +127,9 @@ void menu_media() { if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { if (_menuLineNr == _thisItemNr) { card.getfilename_sorted(SD_ORDER(i, fileCnt)); - MENU_ITEM_IF (card.flag.filenameIsDir) + if (card.flag.filenameIsDir) MENU_ITEM(sdfolder, MSG_MEDIA_MENU, card); - MENU_ITEM_ELSE + else MENU_ITEM(sdfile, MSG_MEDIA_MENU, card); } else diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 63533ee22c..be2effafd6 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -217,7 +217,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); - MENU_ITEM_IF (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { + if (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { extern const char NUL_STR[]; SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); MENU_ITEM_ADDON_START(0 + ENABLED(HAS_CHARACTER_LCD)); @@ -271,23 +271,23 @@ void menu_move() { } #elif EXTRUDERS == 3 if (active_extruder < 2) { - MENU_ITEM_IF (active_extruder) + if (active_extruder) GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); - MENU_ITEM_ELSE + else GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); } #else - MENU_ITEM_IF (active_extruder) + if (active_extruder) GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); - MENU_ITEM_ELSE + else GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); #endif #elif ENABLED(DUAL_X_CARRIAGE) - MENU_ITEM_IF (active_extruder) + if (active_extruder) GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); - MENU_ITEM_ELSE + else GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); #endif @@ -335,7 +335,7 @@ void menu_motion() { // // Move Axis // - MENU_ITEM_IF (TERN1(DELTA, all_axes_homed())) + if (TERN1(DELTA, all_axes_homed())) SUBMENU(MSG_MOVE_AXIS, menu_move); // @@ -364,7 +364,7 @@ void menu_motion() { #elif ENABLED(LCD_BED_LEVELING) - MENU_ITEM_IF (!g29_in_progress) + if (!g29_in_progress) SUBMENU(MSG_BED_LEVELING, menu_bed_leveling); #elif HAS_LEVELING && DISABLED(SLIM_LCD_MENUS) @@ -373,16 +373,14 @@ void menu_motion() { GCODES_ITEM(MSG_LEVEL_BED, PSTR("G28\nG29")); #endif - MENU_ITEM_IF (all_axes_homed() && leveling_is_valid()) { + if (all_axes_homed() && leveling_is_valid()) { bool show_state = planner.leveling_active; EDIT_ITEM(bool, MSG_BED_LEVELING, &show_state, _lcd_toggle_bed_leveling); } #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - MENU_ITEM_IF(1) { - editable.decimal = planner.z_fade_height; - EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); - } + editable.decimal = planner.z_fade_height; + EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 5526848939..e95a7cf22f 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -154,6 +154,11 @@ void Temperature::lcd_preheat(const int16_t e, const int8_t indh, const int8_t i #endif // HAS_TEMP_HOTEND || HAS_HEATED_BED void menu_temperature() { + #if HAS_TEMP_HOTEND + bool has_heat = false; + HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } + #endif + START_MENU(); BACK_ITEM(MSG_MAIN); @@ -198,10 +203,8 @@ void menu_temperature() { #if HAS_FAN1 || HAS_FAN2 || HAS_FAN3 || HAS_FAN4 || HAS_FAN5 || HAS_FAN6 || HAS_FAN7 auto fan_edit_items = [&](const uint8_t f) { - MENU_ITEM_IF(1) { - editable.uint8 = thermalManager.fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); - } + editable.uint8 = thermalManager.fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, f, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[f], 3, 255); #endif @@ -211,18 +214,14 @@ void menu_temperature() { #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && EXTRUDERS > N) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) auto singlenozzle_item = [&](const uint8_t f) { - MENU_ITEM_IF(1) { - editable.uint8 = singlenozzle_fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); - } + editable.uint8 = singlenozzle_fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); }; #endif #if HAS_FAN0 - MENU_ITEM_IF(1) { - editable.uint8 = thermalManager.fan_speed[0]; - EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); - } + editable.uint8 = thermalManager.fan_speed[0]; + EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255); #endif @@ -281,12 +280,8 @@ void menu_temperature() { // // Cooldown // - MENU_ITEM_IF(1) { - bool has_heat = false; - HOTEND_LOOP() if (thermalManager.temp_hotend[HOTEND_INDEX].target) { has_heat = true; break; } - if (TERN0(HAS_HEATED_BED, thermalManager.temp_bed.target)) has_heat = true; - if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); - } + if (TERN0(HAS_HEATED_BED, thermalManager.temp_bed.target)) has_heat = true; + if (has_heat) ACTION_ITEM(MSG_COOLDOWN, lcd_cooldown); #endif // HAS_TEMP_HOTEND diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index e510bae634..b391335259 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -147,10 +147,8 @@ void menu_tune() { #if HAS_FAN1 || HAS_FAN2 || HAS_FAN3 || HAS_FAN4 || HAS_FAN5 || HAS_FAN6 || HAS_FAN7 auto fan_edit_items = [&](const uint8_t f) { - MENU_ITEM_IF(1) { - editable.uint8 = thermalManager.fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); - } + editable.uint8 = thermalManager.fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update); #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, f, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[f], 3, 255); #endif @@ -160,18 +158,14 @@ void menu_tune() { #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && EXTRUDERS > N) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) auto singlenozzle_item = [&](const uint8_t f) { - MENU_ITEM_IF(1) { - editable.uint8 = singlenozzle_fan_speed[f]; - EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); - } + editable.uint8 = singlenozzle_fan_speed[f]; + EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update); }; #endif #if HAS_FAN0 - MENU_ITEM_IF(1) { - editable.uint8 = thermalManager.fan_speed[0]; - EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); - } + editable.uint8 = thermalManager.fan_speed[0]; + EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update); #if ENABLED(EXTRA_FAN_SPEED) EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index fdb0da0b3c..521487c3de 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -579,9 +579,9 @@ void _lcd_ubl_step_by_step() { void _lcd_ubl_level_bed() { START_MENU(); BACK_ITEM(MSG_MOTION); - MENU_ITEM_IF (planner.leveling_active) + if (planner.leveling_active) GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); - MENU_ITEM_ELSE + else GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); SUBMENU(MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step); ACTION_ITEM(MSG_UBL_MESH_EDIT, _lcd_ubl_output_map_lcd_cmd); From 391f7fd7429112992969a310d50c8ea1f726ca0c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 30 Apr 2020 00:03:19 +0000 Subject: [PATCH 0338/1454] [cron] Bump distribution date (2020-04-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e7014c02a4..563fee6bb7 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-29" + #define STRING_DISTRIBUTION_DATE "2020-04-30" #endif /** From b335c3816236bdac6b386aba0e703840545ec778 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 16:14:27 -0500 Subject: [PATCH 0339/1454] Drop extra Marduino includes --- Marlin/src/HAL/AVR/Servo.cpp | 1 - Marlin/src/HAL/DUE/Servo.cpp | 1 - Marlin/src/HAL/SAMD51/Servo.cpp | 1 - 3 files changed, 3 deletions(-) diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp index 02c131bd44..1d4d2034b2 100644 --- a/Marlin/src/HAL/AVR/Servo.cpp +++ b/Marlin/src/HAL/AVR/Servo.cpp @@ -59,7 +59,6 @@ #include -#include "../shared/Marduino.h" #include "../shared/servo.h" #include "../shared/servo_private.h" diff --git a/Marlin/src/HAL/DUE/Servo.cpp b/Marlin/src/HAL/DUE/Servo.cpp index 266158bbc6..6f965783ce 100644 --- a/Marlin/src/HAL/DUE/Servo.cpp +++ b/Marlin/src/HAL/DUE/Servo.cpp @@ -44,7 +44,6 @@ #if HAS_SERVOS -#include "../shared/Marduino.h" #include "../shared/servo.h" #include "../shared/servo_private.h" diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index c7cff45434..b4e22d7f1b 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -29,7 +29,6 @@ #if HAS_SERVOS -#include "../shared/Marduino.h" #include "../shared/servo.h" #include "../shared/servo_private.h" #include "SAMD51.h" From a521b0edbb27c86b344e20768147a157c98a3668 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 16:20:07 -0500 Subject: [PATCH 0340/1454] Strip never-used eeprom functions --- Marlin/src/HAL/shared/eeprom_if.h | 2 -- Marlin/src/HAL/shared/eeprom_if_i2c.cpp | 46 ------------------------- Marlin/src/HAL/shared/eeprom_if_spi.cpp | 40 --------------------- 3 files changed, 88 deletions(-) diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index e6e7046011..1a6b0c97fb 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -26,5 +26,3 @@ // void eeprom_write_byte(uint8_t *pos, unsigned char value); uint8_t eeprom_read_byte(uint8_t *pos); -void eeprom_read_block(void *__dst, const void *__src, size_t __n); -void eeprom_update_block(const void *__src, void *__dst, size_t __n); diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index a4ad9763ba..e2435a7122 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -68,37 +68,6 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) { delay(EEPROM_WRITE_DELAY); } -// WARNING: address is a page address, 6-bit end will wrap around -// also, data can be maximum of about 30 bytes, because the Wire library has a buffer of 32 bytes -void eeprom_update_block(const void *pos, void *__dst, size_t n) { - const unsigned eeprom_address = (unsigned)__dst; - - eeprom_init(); - - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // MSB - Wire.write(int(eeprom_address & 0xFF)); // LSB - Wire.endTransmission(); - - uint8_t *ptr = (uint8_t*)pos; - uint8_t flag = 0; - Wire.requestFrom(eeprom_device_address, (byte)n); - for (byte c = 0; c < n && Wire.available(); c++) - flag |= Wire.read() ^ ptr[c]; - - if (flag) { - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // MSB - Wire.write(int(eeprom_address & 0xFF)); // LSB - Wire.write((uint8_t*)pos, n); - Wire.endTransmission(); - - // wait for write cycle to complete - // this could be done more efficiently with "acknowledge polling" - delay(EEPROM_WRITE_DELAY); - } -} - uint8_t eeprom_read_byte(uint8_t *pos) { const unsigned eeprom_address = (unsigned)pos; @@ -110,19 +79,4 @@ uint8_t eeprom_read_byte(uint8_t *pos) { return Wire.available() ? Wire.read() : 0xFF; } -// Don't read more than 30..32 bytes at a time! -void eeprom_read_block(void* pos, const void *__dst, size_t n) { - const unsigned eeprom_address = (unsigned)__dst; - - eeprom_init(); - - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // MSB - Wire.write(int(eeprom_address & 0xFF)); // LSB - Wire.endTransmission(); - Wire.requestFrom(eeprom_device_address, (byte)n); - for (byte c = 0; c < n; c++ ) - if (Wire.available()) *((uint8_t*)pos + c) = Wire.read(); -} - #endif // USE_SHARED_EEPROM && I2C_EEPROM diff --git a/Marlin/src/HAL/shared/eeprom_if_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp index 4c3a92e020..6a3c5cc059 100644 --- a/Marlin/src/HAL/shared/eeprom_if_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp @@ -58,24 +58,6 @@ uint8_t eeprom_read_byte(uint8_t* pos) { return v; } -void eeprom_read_block(void* dest, const void* eeprom_address, size_t n) { - uint8_t eeprom_temp[3]; - - // set read location - // begin transmission from device - eeprom_temp[0] = CMD_READ; - eeprom_temp[1] = ((unsigned)eeprom_address>>8) & 0xFF; // addr High - eeprom_temp[2] = (unsigned)eeprom_address& 0xFF; // addr Low - WRITE(SPI_EEPROM1_CS, HIGH); - WRITE(SPI_EEPROM1_CS, LOW); - spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3); - - uint8_t *p_dest = (uint8_t *)dest; - while (n--) - *p_dest++ = spiRec(SPI_CHAN_EEPROM1); - WRITE(SPI_EEPROM1_CS, HIGH); -} - void eeprom_write_byte(uint8_t* pos, uint8_t value) { uint8_t eeprom_temp[3]; @@ -98,26 +80,4 @@ void eeprom_write_byte(uint8_t* pos, uint8_t value) { delay(EEPROM_WRITE_DELAY); // wait for page write to complete } -void eeprom_update_block(const void* src, void* eeprom_address, size_t n) { - uint8_t eeprom_temp[3]; - - /*write enable*/ - eeprom_temp[0] = CMD_WREN; - WRITE(SPI_EEPROM1_CS, LOW); - spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 1); - WRITE(SPI_EEPROM1_CS, HIGH); - delay(1); - - /*write addr*/ - eeprom_temp[0] = CMD_WRITE; - eeprom_temp[1] = ((unsigned)eeprom_address>>8) & 0xFF; //addr High - eeprom_temp[2] = (unsigned)eeprom_address & 0xFF; //addr Low - WRITE(SPI_EEPROM1_CS, LOW); - spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3); - - spiSend(SPI_CHAN_EEPROM1, (const uint8_t*)src, n); - WRITE(SPI_EEPROM1_CS, HIGH); - delay(EEPROM_WRITE_DELAY); // wait for page write to complete -} - #endif // USE_SHARED_EEPROM && I2C_EEPROM From 3c080ee3e6c6b73a9867cbd05456b77aab5caae9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Apr 2020 17:33:20 -0500 Subject: [PATCH 0341/1454] Cleanup, comment "wired" eeproms --- Marlin/src/HAL/AVR/eeprom.cpp | 5 +++++ Marlin/src/HAL/DUE/eeprom_wired.cpp | 5 +++++ Marlin/src/HAL/LPC1768/eeprom_wired.cpp | 13 ++++++++----- Marlin/src/HAL/SAMD51/eeprom_wired.cpp | 5 +++++ Marlin/src/HAL/STM32/eeprom_wired.cpp | 9 ++++++++- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 5 +++++ .../STM32_F4_F7/{eeprom.cpp => eeprom_wired.cpp} | 13 +++++++++++-- Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h | 1 - Marlin/src/HAL/TEENSY31_32/eeprom.cpp | 5 +++++ Marlin/src/HAL/TEENSY35_36/eeprom.cpp | 5 +++++ 10 files changed, 57 insertions(+), 9 deletions(-) rename Marlin/src/HAL/STM32_F4_F7/{eeprom.cpp => eeprom_wired.cpp} (90%) diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index e946668054..0519e5732e 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -25,6 +25,11 @@ #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +/** + * PersistentStore for Arduino-style EEPROM interface + * with implementations supplied by the framework. + */ + #include "../shared/eeprom_api.h" size_t PersistentStore::capacity() { return E2END + 1; } diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index 429d8df374..a9b2cc92d2 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -26,6 +26,11 @@ #if USE_WIRED_EEPROM +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index f5db53434d..e0f72b78e5 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -25,20 +25,25 @@ #if USE_WIRED_EEPROM -#include "../shared/eeprom_if.h" +/** + * PersistentStore for Arduino-style EEPROM interface + * with implementations supplied by the framework. + */ + #include "../shared/eeprom_api.h" #ifndef EEPROM_SIZE #define EEPROM_SIZE 0x8000 // 32kB‬ #endif +size_t PersistentStore::capacity() { return EEPROM_SIZE; } +bool PersistentStore::access_finish() { return true; } + bool PersistentStore::access_start() { TERN_(SPI_EEPROM, eeprom_init()); return true; } -bool PersistentStore::access_finish() { return true; } - bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t v = *value; @@ -75,7 +80,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { return EEPROM_SIZE; } - #endif // USE_WIRED_EEPROM #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp index 9dc83f37e6..8c94422422 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp @@ -24,6 +24,11 @@ #if USE_WIRED_EEPROM +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index 465cf44a25..5639e532cc 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -26,14 +26,21 @@ #if USE_WIRED_EEPROM +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } +bool PersistentStore::access_start() { + return true; +} + bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t v = *value; diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index e53e9d8674..8d584c67b0 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -23,6 +23,11 @@ #if USE_WIRED_EEPROM +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp similarity index 90% rename from Marlin/src/HAL/STM32_F4_F7/eeprom.cpp rename to Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp index 370d2885ae..7eb06ebdde 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp @@ -24,7 +24,12 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) +#if USE_WIRED_EEPROM + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" @@ -33,6 +38,10 @@ size_t PersistentStore::capacity() { return E2END + 1; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } +bool PersistentStore::access_start() { + return true; +} + bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t * const p = (uint8_t * const)pos; @@ -64,5 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -#endif // EEPROM_SETTINGS +#endif // USE_WIRED_EEPROM #endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h index a96352376e..d21624955e 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h @@ -26,5 +26,4 @@ #undef SRAM_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION - #warning "Forcing use of FLASH_EEPROM_EMULATION." #endif diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp index a00c1062aa..5e3c8bfcfc 100644 --- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp @@ -22,6 +22,11 @@ #if USE_WIRED_EEPROM +/** + * PersistentStore for Arduino-style EEPROM interface + * with implementations supplied by the framework. + */ + #include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index ff8fa3626d..9926745511 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -26,6 +26,11 @@ #if USE_WIRED_EEPROM +/** + * PersistentStore for Arduino-style EEPROM interface + * with implementations supplied by the framework. + */ + #include "../shared/eeprom_api.h" #include From 7f5730ea3b5b3b3027b5335a3e6590565c2d094a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Apr 2020 16:31:58 -0500 Subject: [PATCH 0342/1454] Minimal interface for F4/F7 flash --- Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp | 7 +- Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h | 1 - .../{eeprom_if_flash.cpp => eeprom_flash.cpp} | 81 +++++++++---------- 3 files changed, 44 insertions(+), 45 deletions(-) rename Marlin/src/HAL/STM32_F4_F7/{eeprom_if_flash.cpp => eeprom_flash.cpp} (63%) diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp index cb4811d2aa..3e74203aec 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp @@ -49,7 +49,7 @@ */ #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) @@ -65,7 +65,7 @@ uint16_t DataVar = 0; uint16_t VirtAddVarTab[NB_OF_VAR]; /* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ + static HAL_StatusTypeDef EE_Format(); static uint16_t EE_FindValidPage(uint8_t Operation); static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data); @@ -79,6 +79,9 @@ static uint16_t EE_VerifyPageFullyErased(uint32_t Address); * @retval - Flash error code: on write Flash error * - FLASH_COMPLETE: on success */ + +/* Private functions ---------------------------------------------------------*/ + uint16_t EE_Initialize() { /* Get Page0 and Page1 status */ uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS), diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h index e4094f8e13..84c4c6e3d2 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h @@ -50,7 +50,6 @@ // ------------------------ #include "../../inc/MarlinConfig.h" -#include "HAL.h" /* Exported constants --------------------------------------------------------*/ /* EEPROM emulation firmware error codes */ diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_if_flash.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp similarity index 63% rename from Marlin/src/HAL/STM32_F4_F7/eeprom_if_flash.cpp rename to Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp index 86b80f2b8b..cd5648c73a 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_if_flash.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp @@ -18,26 +18,12 @@ */ #if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) -/** - * Arduino-style interface for Flash emulated EEPROM - */ - -// Include configs and pins to get all EEPROM flags #include "../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) -// ------------------------ -// Includes -// ------------------------ - -#include "HAL.h" +#include "../shared/eeprom_api.h" #include "eeprom_emul.h" -#include "../shared/eeprom_if.h" - -// ------------------------ -// Local defines -// ------------------------ // FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to // FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F4/7 @@ -48,18 +34,9 @@ //#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR #endif -// ------------------------ -// Private Variables -// ------------------------ - -static bool eeprom_initialized = false; - -// ------------------------ -// Public functions -// ------------------------ - -void eeprom_init() { - if (!eeprom_initialized) { +void ee_init() { + static bool ee_initialized = false; + if (!ee_initialized) { HAL_FLASH_Unlock(); __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); @@ -69,12 +46,12 @@ void eeprom_init() { for (;;) HAL_Delay(1); // Spin forever until watchdog reset HAL_FLASH_Lock(); - eeprom_initialized = true; + ee_initialized = true; } } -void eeprom_write_byte(uint8_t *pos, unsigned char value) { - eeprom_init(); +void ee_write_byte(uint8_t *pos, unsigned char value) { + ee_init(); HAL_FLASH_Unlock(); __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); @@ -86,8 +63,8 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) { HAL_FLASH_Lock(); } -uint8_t eeprom_read_byte(uint8_t *pos) { - eeprom_init(); +uint8_t ee_read_byte(uint8_t *pos) { + ee_init(); uint16_t data = 0xFF; const unsigned eeprom_address = (unsigned)pos; @@ -96,19 +73,39 @@ uint8_t eeprom_read_byte(uint8_t *pos) { return uint8_t(data); } -void eeprom_read_block(void *__dst, const void *__src, size_t __n) { - eeprom_init(); +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } - uint16_t data = 0xFF; - const unsigned eeprom_address = (unsigned)__src; - LOOP_L_N(c, __n) { - EE_ReadVariable(eeprom_address+c, &data); - *((uint8_t*)__dst + c) = data; - } +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t * const p = (uint8_t * const)pos; + uint8_t v = *value; + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != ee_read_byte(p)) { + ee_write_byte(p, v); + if (ee_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + }; + return false; } -void eeprom_update_block(const void *__src, void *__dst, size_t __n) { - +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + uint8_t c = ee_read_byte((uint8_t*)pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; } #endif // FLASH_EEPROM_EMULATION From bd8436d1c54e347881ea632e233175c58160ffc4 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Fri, 1 May 2020 01:14:49 +0200 Subject: [PATCH 0343/1454] Fix SAMD51 i2c EEPROM (#17815) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/SAMD51/eeprom_wired.cpp | 6 +++++- Marlin/src/HAL/shared/eeprom_if.h | 1 + Marlin/src/HAL/shared/eeprom_if_i2c.cpp | 2 +- 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp index 8c94422422..e5c14e9cbf 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp @@ -33,9 +33,13 @@ #include "../shared/eeprom_api.h" size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } +bool PersistentStore::access_start() { + eeprom_init(); + return true; +} + bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { const uint8_t v = *value; diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index 1a6b0c97fb..bf690f9a88 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -24,5 +24,6 @@ // // EEPROM // +void eeprom_init(); void eeprom_write_byte(uint8_t *pos, unsigned char value); uint8_t eeprom_read_byte(uint8_t *pos); diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index e2435a7122..0f429b7c67 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -52,7 +52,7 @@ static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRE // Public functions // ------------------------ -static void eeprom_init() { Wire.begin(); } +void eeprom_init() { Wire.begin(); } void eeprom_write_byte(uint8_t *pos, unsigned char value) { const unsigned eeprom_address = (unsigned)pos; From 9b820d71a62a6f826beff0b230b1aefc4c350212 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Apr 2020 18:15:52 -0500 Subject: [PATCH 0344/1454] Remove QSPI from "wired" EEPROM type --- Marlin/src/inc/Conditionals_post.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 844b291429..f66c2f16ad 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -39,9 +39,9 @@ #if ENABLED(EEPROM_SETTINGS) // EEPROM type may be defined by compile flags, configs, HALs, or pins // Set additional flags to let HALs choose in their Conditionals_post.h - #if ANY(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #if ANY(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION, QSPI_EEPROM) #define USE_EMULATED_EEPROM 1 - #elif ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM) + #elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_WIRED_EEPROM 1 #else #define USE_FALLBACK_EEPROM 1 From 0b762189b462d3862a9660ac06193263c2e6c088 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Fri, 1 May 2020 01:18:23 +0200 Subject: [PATCH 0345/1454] Change RAMPS default filament runout pin (#17814) --- Marlin/src/pins/samd/pins_RAMPS_144.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index f02a8b86bd..082c0412e3 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -129,9 +129,8 @@ #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif -// RAMPS 1.4 DIO 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 71 #endif #ifndef PS_ON_PIN From 3efbe9a1c4c80a6e2b52eb62d8cbe1da1f0b7e25 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 1 May 2020 00:03:30 +0000 Subject: [PATCH 0346/1454] [cron] Bump distribution date (2020-05-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 563fee6bb7..a3cf749ccc 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-04-30" + #define STRING_DISTRIBUTION_DATE "2020-05-01" #endif /** From 306578d7be75a23c5b745142023d1aa5c68c79ca Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Apr 2020 19:18:58 -0500 Subject: [PATCH 0347/1454] More explicit LPC timer defines --- Marlin/src/HAL/LPC1768/timers.h | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 30da933521..f99418c1c3 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -88,8 +88,8 @@ typedef uint32_t hal_timer_t; #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM) // Timer references by index -#define STEP_TIMER _HAL_TIMER(STEP_TIMER_NUM) -#define TEMP_TIMER _HAL_TIMER(TEMP_TIMER_NUM) +#define STEP_TIMER_PTR _HAL_TIMER(STEP_TIMER_NUM) +#define TEMP_TIMER_PTR _HAL_TIMER(TEMP_TIMER_NUM) // ------------------------ // Public functions @@ -99,23 +99,23 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case 0: STEP_TIMER->MR0 = compare; break; // Stepper Timer Match Register 0 - case 1: TEMP_TIMER->MR0 = compare; break; // Temp Timer Match Register 0 + case 0: STEP_TIMER_PTR->MR0 = compare; break; // Stepper Timer Match Register 0 + case 1: TEMP_TIMER_PTR->MR0 = compare; break; // Temp Timer Match Register 0 } } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { switch (timer_num) { - case 0: return STEP_TIMER->MR0; // Stepper Timer Match Register 0 - case 1: return TEMP_TIMER->MR0; // Temp Timer Match Register 0 + case 0: return STEP_TIMER_PTR->MR0; // Stepper Timer Match Register 0 + case 1: return TEMP_TIMER_PTR->MR0; // Temp Timer Match Register 0 } return 0; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { switch (timer_num) { - case 0: return STEP_TIMER->TC; // Stepper Timer Count - case 1: return TEMP_TIMER->TC; // Temp Timer Count + case 0: return STEP_TIMER_PTR->TC; // Stepper Timer Count + case 1: return TEMP_TIMER_PTR->TC; // Temp Timer Count } return 0; } @@ -154,8 +154,8 @@ FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case 0: SBI(STEP_TIMER->IR, SBIT_CNTEN); break; - case 1: SBI(TEMP_TIMER->IR, SBIT_CNTEN); break; + case 0: SBI(STEP_TIMER_PTR->IR, SBIT_CNTEN); break; + case 1: SBI(TEMP_TIMER_PTR->IR, SBIT_CNTEN); break; } } From 76bc7bf7b8759e2e2dd2975de929137d5eb135c9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Apr 2020 20:09:51 -0500 Subject: [PATCH 0348/1454] Pre-clean DUE flash eeprom code --- Marlin/src/HAL/DUE/eeprom_if_flash.cpp | 165 +++++++++++-------------- Marlin/src/core/debug_out.h | 3 + 2 files changed, 78 insertions(+), 90 deletions(-) diff --git a/Marlin/src/HAL/DUE/eeprom_if_flash.cpp b/Marlin/src/HAL/DUE/eeprom_if_flash.cpp index 8464ed62bb..f91bfda668 100644 --- a/Marlin/src/HAL/DUE/eeprom_if_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_if_flash.cpp @@ -19,6 +19,15 @@ * along with this program. If not, see . * */ +#ifdef ARDUINO_ARCH_SAM + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(FLASH_EEPROM_EMULATION) + +#include "../shared/Marduino.h" +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" /* EEPROM emulation over flash with reduced wear * @@ -50,15 +59,7 @@ * */ -#ifdef ARDUINO_ARCH_SAM - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - -#include "../shared/Marduino.h" -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +//#define EE_EMU_DEBUG #define EEPROMSize 4096 #define PagesPerGroup 128 @@ -135,15 +136,18 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes curPage = 0, // Current FLASH page inside the group curGroup = 0xFF; // Current FLASH group -//#define EE_EMU_DEBUG -#ifdef EE_EMU_DEBUG - static void ee_Dump(int page,const void* data) { +#define DEBUG_OUT ENABLED(EE_EMU_DEBUG) +#include "../../core/debug_out.h" + +static void ee_Dump(const int page, const void* data) { + + #ifdef EE_EMU_DEBUG const uint8_t* c = (const uint8_t*) data; char buffer[80]; sprintf_P(buffer, PSTR("Page: %d (0x%04x)\n"), page, page); - SERIAL_ECHO(buffer); + DEBUG_ECHO(buffer); char* p = &buffer[0]; for (int i = 0; i< PageSize; ++i) { @@ -153,12 +157,16 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes if ((i & 0xF) == 0xF) { *p++ = '\n'; *p = 0; - SERIAL_ECHO(buffer); + DEBUG_ECHO(buffer); p = &buffer[0]; } } - } -#endif + + #else + UNUSED(page); + UNUSED(data); + #endif +} /* Flash Writing Protection Key */ #define FWP_KEY 0x5Au @@ -171,17 +179,16 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes #define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE) #endif - /** * Writes the contents of the specified page (no previous erase) * @param page (page #) * @param data (pointer to the data buffer) */ __attribute__ ((long_call, section (".ramfunc"))) -static bool ee_PageWrite(uint16_t page,const void* data) { +static bool ee_PageWrite(uint16_t page, const void* data) { uint16_t i; - uint32_t addrflash = ((uint32_t)getFlashStorage(page)); + uint32_t addrflash = uint32_t(getFlashStorage(page)); // Read the flash contents uint32_t pageContents[PageSize>>2]; @@ -196,13 +203,11 @@ static bool ee_PageWrite(uint16_t page,const void* data) { for (i = 0; i > 2; i++) pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i])); - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM PageWrite ", page); - SERIAL_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); - SERIAL_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); - SERIAL_FLUSH(); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM PageWrite ", page); + DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); + DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); + DEBUG_FLUSH(); // Get the page relative to the start of the EFC controller, and the EFC controller to use Efc *efc; @@ -244,10 +249,8 @@ static bool ee_PageWrite(uint16_t page,const void* data) { // Reenable interrupts __enable_irq(); - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Unlock failure for page ", page); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ", page); return false; } @@ -271,10 +274,9 @@ static bool ee_PageWrite(uint16_t page,const void* data) { // Reenable interrupts __enable_irq(); - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Write failure for page ", page); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Write failure for page ", page); + return false; } @@ -288,11 +290,11 @@ static bool ee_PageWrite(uint16_t page,const void* data) { if (memcmp(getFlashStorage(page),data,PageSize)) { #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Verify Write failure for page ", page); + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Verify Write failure for page ", page); - ee_Dump( page,(uint32_t *) addrflash); - ee_Dump(-page,data); + ee_Dump( page, (uint32_t *)addrflash); + ee_Dump(-page, data); // Calculate count of changed bits uint32_t* p1 = (uint32_t*)addrflash; @@ -308,7 +310,7 @@ static bool ee_PageWrite(uint16_t page,const void* data) { } } } - SERIAL_ECHOLNPAIR("--> Differing bits: ", count); + DEBUG_ECHOLNPAIR("--> Differing bits: ", count); #endif return false; @@ -325,15 +327,13 @@ __attribute__ ((long_call, section (".ramfunc"))) static bool ee_PageErase(uint16_t page) { uint16_t i; - uint32_t addrflash = ((uint32_t)getFlashStorage(page)); + uint32_t addrflash = uint32_t(getFlashStorage(page)); - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM PageErase ", page); - SERIAL_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); - SERIAL_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); - SERIAL_FLUSH(); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM PageErase ", page); + DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); + DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); + DEBUG_FLUSH(); // Get the page relative to the start of the EFC controller, and the EFC controller to use Efc *efc; @@ -374,10 +374,9 @@ static bool ee_PageErase(uint16_t page) { // Reenable interrupts __enable_irq(); - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Unlock failure for page ",page); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ",page); + return false; } @@ -399,10 +398,9 @@ static bool ee_PageErase(uint16_t page) { // Reenable interrupts __enable_irq(); - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Erase failure for page ",page); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Erase failure for page ",page); + return false; } @@ -416,20 +414,17 @@ static bool ee_PageErase(uint16_t page) { uint32_t * aligned_src = (uint32_t *) addrflash; for (i = 0; i < PageSize >> 2; i++) { if (*aligned_src++ != 0xFFFFFFFF) { - - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page); - - ee_Dump( page,(uint32_t *) addrflash); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page); + ee_Dump(page, (uint32_t *)addrflash); return false; } } return true; } -static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer = false) { + +static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer=false) { uint32_t baddr; uint32_t blen; @@ -512,7 +507,7 @@ static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer = false) { return 0xFF; } -static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer = false) { +static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) { uint32_t baddr, blen, nextAddr = 0xFFFF, @@ -604,7 +599,7 @@ static bool ee_IsPageClean(int page) { return true; } -static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData = 0xFF) { +static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData=0xFF) { // Check if RAM buffer has something to be written bool isEmpty = true; @@ -930,11 +925,9 @@ static void ee_Init() { // If all groups seem to be used, default to first group if (curGroup >= GroupCount) curGroup = 0; - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Current Group: ",curGroup); - SERIAL_FLUSH(); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Current Group: ",curGroup); + DEBUG_FLUSH(); // Now, validate that all the other group pages are empty for (int grp = 0; grp < GroupCount; grp++) { @@ -942,11 +935,9 @@ static void ee_Init() { for (int page = 0; page < PagesPerGroup; page++) { if (!ee_IsPageClean(grp * PagesPerGroup + page)) { - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp); - SERIAL_FLUSH(); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp); + DEBUG_FLUSH(); ee_PageErase(grp * PagesPerGroup + page); } } @@ -956,28 +947,22 @@ static void ee_Init() { // and also validate that all the other ones are clean for (curPage = 0; curPage < PagesPerGroup; curPage++) { if (ee_IsPageClean(curGroup * PagesPerGroup + curPage)) { - #ifdef EE_EMU_DEBUG - ee_Dump(curGroup * PagesPerGroup + curPage, getFlashStorage(curGroup * PagesPerGroup + curPage)); - #endif + ee_Dump(curGroup * PagesPerGroup + curPage, getFlashStorage(curGroup * PagesPerGroup + curPage)); break; } } - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Active page: ", curPage); - SERIAL_FLUSH(); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Active page: ", curPage); + DEBUG_FLUSH(); // Make sure the pages following the first clean one are also clean for (int page = curPage + 1; page < PagesPerGroup; page++) { if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) { - #ifdef EE_EMU_DEBUG - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup); - SERIAL_FLUSH(); - ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page)); - #endif + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup); + DEBUG_FLUSH(); + ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page)); ee_PageErase(curGroup * PagesPerGroup + page); } } @@ -1018,4 +1003,4 @@ void eeprom_flush() { } #endif // FLASH_EEPROM_EMULATION -#endif // ARDUINO_ARCH_AVR +#endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h index 4b2cdf9f77..b7506a8304 100644 --- a/Marlin/src/core/debug_out.h +++ b/Marlin/src/core/debug_out.h @@ -46,6 +46,7 @@ #undef DEBUG_ECHO_MSG #undef DEBUG_ERROR_MSG #undef DEBUG_EOL +#undef DEBUG_FLUSH #undef DEBUG_POS #undef DEBUG_XYZ #undef DEBUG_DELAY @@ -71,6 +72,7 @@ #define DEBUG_ECHO_MSG SERIAL_ECHO_MSG #define DEBUG_ERROR_MSG SERIAL_ERROR_MSG #define DEBUG_EOL SERIAL_EOL + #define DEBUG_FLUSH SERIAL_FLUSH #define DEBUG_POS SERIAL_POS #define DEBUG_XYZ SERIAL_XYZ #define DEBUG_DELAY(ms) serial_delay(ms) @@ -95,6 +97,7 @@ #define DEBUG_ECHO_MSG(...) NOOP #define DEBUG_ERROR_MSG(...) NOOP #define DEBUG_EOL() NOOP + #define DEBUG_FLUSH() NOOP #define DEBUG_POS(...) NOOP #define DEBUG_XYZ(...) NOOP #define DEBUG_DELAY(...) NOOP From b4aebbe78d67ec16e63bcc5240aa50c351519012 Mon Sep 17 00:00:00 2001 From: "J.C. Nelson" <32139633+xC0000005@users.noreply.github.com> Date: Thu, 30 Apr 2020 20:42:40 -0700 Subject: [PATCH 0349/1454] Allow STM32 pins to specify timers (#17805) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/STM32/timers.cpp | 44 +++++++++++- Marlin/src/HAL/STM32/timers.h | 80 ---------------------- Marlin/src/pins/stm32f0/pins_MALYAN_M300.h | 2 - Marlin/src/pins/stm32f1/pins_MALYAN_M200.h | 2 - 4 files changed, 42 insertions(+), 86 deletions(-) diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index ad46e34b71..3bbef2c609 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -21,21 +21,61 @@ */ #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) -#include "HAL.h" - #include "timers.h" +#include "../../inc/MarlinConfig.h" + // ------------------------ // Local defines // ------------------------ #define NUM_HARDWARE_TIMERS 2 +#ifndef SWSERIAL_TIMER_IRQ_PRIO + #define SWSERIAL_TIMER_IRQ_PRIO 1 +#endif +#ifndef STEP_TIMER_IRQ_PRIO + #define STEP_TIMER_IRQ_PRIO 2 +#endif +#ifndef TEMP_TIMER_IRQ_PRIO + #define TEMP_TIMER_IRQ_PRIO 14 // 14 = after hardware ISRs +#endif + +#ifdef STM32F0xx + #define HAL_TIMER_RATE (F_CPU) // Frequency of timer peripherals + #define MCU_STEP_TIMER 16 + #define MCU_TEMP_TIMER 17 +#elif defined(STM32F1xx) + #define HAL_TIMER_RATE (F_CPU) + #define MCU_STEP_TIMER 4 + #define MCU_TEMP_TIMER 2 +#elif defined(STM32F401xC) || defined(STM32F401xE) + #define HAL_TIMER_RATE (F_CPU / 2) + #define MCU_STEP_TIMER 9 + #define MCU_TEMP_TIMER 10 +#elif defined(STM32F4xx) || defined(STM32F7xx) + #define HAL_TIMER_RATE (F_CPU / 2) + #define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8 + #define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used. +#endif + +#ifndef STEP_TIMER + #define STEP_TIMER MCU_STEP_TIMER +#endif +#ifndef TEMP_TIMER + #define TEMP_TIMER MCU_TEMP_TIMER +#endif + #define __TIMER_DEV(X) TIM##X #define _TIMER_DEV(X) __TIMER_DEV(X) #define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER) #define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER) +#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn +#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X) +#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER) +#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER) + // ------------------------ // Private Variables // ------------------------ diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 8a0950a4d7..6a04359c21 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -33,80 +33,6 @@ #define hal_timer_t uint32_t #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit -#ifdef STM32F0xx - - #define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals - - #ifndef STEP_TIMER - #define STEP_TIMER 16 - #endif - - #ifndef TEMP_TIMER - #define TEMP_TIMER 17 - #endif - -#elif defined(STM32F1xx) - - #define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals - - #ifndef STEP_TIMER - #define STEP_TIMER 4 - #endif - - #ifndef TEMP_TIMER - #define TEMP_TIMER 2 - #endif - -#elif defined(STM32F401xC) || defined(STM32F401xE) - - #define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals - - #ifndef STEP_TIMER - #define STEP_TIMER 9 - #endif - - #ifndef TEMP_TIMER - #define TEMP_TIMER 10 - #endif - -#elif defined(STM32F4xx) - - #define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals - - #ifndef STEP_TIMER - #define STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8 - #endif - - #ifndef TEMP_TIMER - #define TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used. - #endif - -#elif defined(STM32F7xx) - - #define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals - - #ifndef STEP_TIMER - #define STEP_TIMER 6 // the RIGHT timer! - #endif - - #ifndef TEMP_TIMER - #define TEMP_TIMER 14 - #endif - -#endif - -#ifndef SWSERIAL_TIMER_IRQ_PRIO - #define SWSERIAL_TIMER_IRQ_PRIO 1 -#endif - -#ifndef STEP_TIMER_IRQ_PRIO - #define STEP_TIMER_IRQ_PRIO 2 -#endif - -#ifndef TEMP_TIMER_IRQ_PRIO - #define TEMP_TIMER_IRQ_PRIO 14 // 14 = after hardware ISRs -#endif - #define STEP_TIMER_NUM 0 // index of timer to use for stepper #define TEMP_TIMER_NUM 1 // index of timer to use for temperature #define PULSE_TIMER_NUM STEP_TIMER_NUM @@ -122,12 +48,6 @@ #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn -#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X) - -#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER) -#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER) - #define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) #define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index 129a3175bd..88604496d2 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -43,8 +43,6 @@ // // Timers // -#undef STEP_TIMER -#undef TEMP_TIMER #define STEP_TIMER 6 #define TEMP_TIMER 7 diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 00dd2e1184..87f323dfa5 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -42,8 +42,6 @@ // On STM32F103: // PB3, PB6, PB7, and PB8 can be used with pwm, which rules out TIM2 and TIM4. // On STM32F070, 16 and 17 are in use, but 1 and 3 are available. -#undef STEP_TIMER -#undef TEMP_TIMER #define STEP_TIMER 1 #define TEMP_TIMER 3 From 6edc2c3690ff326fa1ada28ea036bb719962bdba Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Apr 2020 22:49:28 -0500 Subject: [PATCH 0350/1454] Fix eeprom init glitch --- Marlin/src/HAL/LPC1768/eeprom_wired.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index e0f72b78e5..677138c688 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -40,7 +40,7 @@ size_t PersistentStore::capacity() { return EEPROM_SIZE; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { - TERN_(SPI_EEPROM, eeprom_init()); + TERN_(I2C_EEPROM, eeprom_init()); return true; } From a226b281aff5d569bc18afb9879149e0e89d29df Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Apr 2020 22:52:33 -0500 Subject: [PATCH 0351/1454] UI and stall reset for extra TMC axes (#17818) --- .../stepper_bump_sensitivity_screen.cpp | 36 ++----- Marlin/src/lcd/extui/ui_api.cpp | 28 +++++- Marlin/src/lcd/extui/ui_api.h | 2 +- Marlin/src/lcd/menu/menu_tmc.cpp | 18 +++- Marlin/src/module/stepper/trinamic.cpp | 98 +++++++------------ 5 files changed, 85 insertions(+), 97 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp index 4edfe9435e..b22d1415b3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp @@ -34,39 +34,21 @@ void StepperBumpSensitivityScreen::onRedraw(draw_mode_t what) { widgets_t w(what); w.precision(0, BaseNumericAdjustmentScreen::DEFAULT_LOWEST); w.heading( GET_TEXT_F(MSG_TMC_HOMING_THRS)); - w.color(x_axis) .adjuster( 2, GET_TEXT_F(MSG_AXIS_X), getTMCBumpSensitivity(X), - #if X_SENSORLESS - true - #else - false - #endif - ); - w.color(y_axis) .adjuster( 4, GET_TEXT_F(MSG_AXIS_Y), getTMCBumpSensitivity(Y), - #if Y_SENSORLESS - true - #else - false - #endif - ); - w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getTMCBumpSensitivity(Z), - #if Z_SENSORLESS - true - #else - false - #endif - ); + w.color(x_axis) .adjuster( 2, GET_TEXT_F(MSG_AXIS_X), getTMCBumpSensitivity(X), ENABLED(X_SENSORLESS)); + w.color(y_axis) .adjuster( 4, GET_TEXT_F(MSG_AXIS_Y), getTMCBumpSensitivity(Y), ENABLED(Y_SENSORLESS)); + w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getTMCBumpSensitivity(Z), ENABLED(Z_SENSORLESS)); w.increments(); } bool StepperBumpSensitivityScreen::onTouchHeld(uint8_t tag) { const float increment = getIncrement(); switch (tag) { - case 2: UI_DECREMENT(TMCBumpSensitivity, X ); break; - case 3: UI_INCREMENT(TMCBumpSensitivity, X ); break; - case 4: UI_DECREMENT(TMCBumpSensitivity, Y ); break; - case 5: UI_INCREMENT(TMCBumpSensitivity, Y ); break; - case 6: UI_DECREMENT(TMCBumpSensitivity, Z ); break; - case 7: UI_INCREMENT(TMCBumpSensitivity, Z ); break; + case 2: UI_DECREMENT(TMCBumpSensitivity, X ); break; + case 3: UI_INCREMENT(TMCBumpSensitivity, X2 ); break; + case 4: UI_DECREMENT(TMCBumpSensitivity, Y ); break; + case 5: UI_INCREMENT(TMCBumpSensitivity, Y2 ); break; + case 6: UI_DECREMENT(TMCBumpSensitivity, Z ); break; + case 7: UI_INCREMENT(TMCBumpSensitivity, Z2 ); break; default: return false; } diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index de043a3198..2b72eca047 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -489,9 +489,14 @@ namespace ExtUI { int getTMCBumpSensitivity(const axis_t axis) { switch (axis) { - TERN_(X_SENSORLESS, case X: return stepperX.homing_threshold()); - TERN_(Y_SENSORLESS, case Y: return stepperY.homing_threshold()); - TERN_(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()); + TERN_(X_SENSORLESS, case X: return stepperX.homing_threshold()); + TERN_(X2_SENSORLESS, case X2: return stepperX2.homing_threshold()); + TERN_(Y_SENSORLESS, case Y: return stepperY.homing_threshold()); + TERN_(Y2_SENSORLESS, case Y2: return stepperY2.homing_threshold()); + TERN_(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()); + TERN_(Z2_SENSORLESS, case Z2: return stepperZ2.homing_threshold()); + TERN_(Z3_SENSORLESS, case Z3: return stepperZ3.homing_threshold()); + TERN_(Z4_SENSORLESS, case Z4: return stepperZ4.homing_threshold()); default: return 0; } } @@ -500,14 +505,29 @@ namespace ExtUI { switch (axis) { #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS #if X_SENSORLESS - case X: stepperX.homing_threshold(value); break; + case X: stepperX.homing_threshold(value); break; + #endif + #if X2_SENSORLESS + case X2: stepperX2.homing_threshold(value); break; #endif #if Y_SENSORLESS case Y: stepperY.homing_threshold(value); break; #endif + #if Y2_SENSORLESS + case Y2: stepperY2.homing_threshold(value); break; + #endif #if Z_SENSORLESS case Z: stepperZ.homing_threshold(value); break; #endif + #if Z2_SENSORLESS + case Z2: stepperZ2.homing_threshold(value); break; + #endif + #if Z3_SENSORLESS + case Z3: stepperZ3.homing_threshold(value); break; + #endif + #if Z4_SENSORLESS + case Z4: stepperZ4.homing_threshold(value); break; + #endif #else UNUSED(value); #endif diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 652f77198a..506157f9af 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -52,7 +52,7 @@ namespace ExtUI { static constexpr size_t eeprom_data_size = 48; - enum axis_t : uint8_t { X, Y, Z }; + enum axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4 }; enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5, E6, E7 }; enum heater_t : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER }; enum fan_t : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 }; diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 296a132e14..f8c6eb3a8a 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -157,15 +157,27 @@ void menu_tmc_current() { BACK_ITEM(MSG_TMC_DRIVERS); #if X_SENSORLESS TMC_EDIT_STORED_SGT(X); - #endif - #if X2_SENSORLESS - TMC_EDIT_STORED_SGT(X2); + #if X2_SENSORLESS + TMC_EDIT_STORED_SGT(X2); + #endif #endif #if Y_SENSORLESS TMC_EDIT_STORED_SGT(Y); + #if Y2_SENSORLESS + TMC_EDIT_STORED_SGT(Y2); + #endif #endif #if Z_SENSORLESS TMC_EDIT_STORED_SGT(Z); + #if Z2_SENSORLESS + TMC_EDIT_STORED_SGT(Z2); + #endif + #if Z3_SENSORLESS + TMC_EDIT_STORED_SGT(Z3); + #endif + #if Z4_SENSORLESS + TMC_EDIT_STORED_SGT(Z4); + #endif #endif END_MENU(); } diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 4f0751ec2e..48a4ff85e9 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -117,16 +117,12 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #endif #ifndef TMC_BAUD_RATE - #if HAS_TMC_SW_SERIAL - // Reduce baud rate for boards not already overriding TMC_BAUD_RATE for software serial. - // Testing has shown that 115200 is not 100% reliable on AVR platforms, occasionally - // failing to read status properly. 32-bit platforms typically define an even lower - // TMC_BAUD_RATE, due to differences in how SoftwareSerial libraries work on different - // platforms. - #define TMC_BAUD_RATE 57600 - #else - #define TMC_BAUD_RATE 115200 - #endif + // Reduce baud rate for boards not already overriding TMC_BAUD_RATE for software serial. + // Testing has shown that 115200 is not 100% reliable on AVR platforms, occasionally + // failing to read status properly. 32-bit platforms typically define an even lower + // TMC_BAUD_RATE, due to differences in how SoftwareSerial libraries work on different + // platforms. + #define TMC_BAUD_RATE TERN(HAS_TMC_SW_SERIAL, 57600, 115200) #endif #if HAS_DRIVER(TMC2130) @@ -158,11 +154,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ampl = 180; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(); // Clear GSTAT } @@ -200,11 +192,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ofs = 36; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(); // Clear GSTAT } @@ -489,11 +477,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ofs = 36; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(0b111); // Clear delay(200); @@ -535,11 +519,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ofs = 36; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(0b111); // Clear delay(200); @@ -597,11 +577,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ampl = 180; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(); // Clear GSTAT } @@ -700,25 +676,7 @@ void restore_trinamic_drivers() { } void reset_trinamic_drivers() { - static constexpr bool stealthchop_by_axis[] = { - #if ENABLED(STEALTHCHOP_XY) - true - #else - false - #endif - , - #if ENABLED(STEALTHCHOP_Z) - true - #else - false - #endif - , - #if ENABLED(STEALTHCHOP_E) - true - #else - false - #endif - }; + static constexpr bool stealthchop_by_axis[] = { ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z), ENABLED(STEALTHCHOP_E) }; #if AXIS_IS_TMC(X) TMC_INIT(X, STEALTH_AXIS_XY); @@ -770,14 +728,30 @@ void reset_trinamic_drivers() { #endif #if USE_SENSORLESS - TERN_(X_SENSORLESS, stepperX.homing_threshold(X_STALL_SENSITIVITY)); - TERN_(X2_SENSORLESS, stepperX2.homing_threshold(X2_STALL_SENSITIVITY)); - TERN_(Y_SENSORLESS, stepperY.homing_threshold(Y_STALL_SENSITIVITY)); - TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(Y2_STALL_SENSITIVITY)); - TERN_(Z_SENSORLESS, stepperZ.homing_threshold(Z_STALL_SENSITIVITY)); - TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(Z2_STALL_SENSITIVITY)); - TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(Z3_STALL_SENSITIVITY)); - TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(Z4_STALL_SENSITIVITY)); + #if X_SENSORLESS + stepperX.homing_threshold(X_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(X2) + stepperX2.homing_threshold(CAT(TERN(X2_SENSORLESS, X2, X), _STALL_SENSITIVITY)); + #endif + #endif + #if Y_SENSORLESS + stepperY.homing_threshold(Y_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(Y2) + stepperY2.homing_threshold(CAT(TERN(Y2_SENSORLESS, Y2, Y), _STALL_SENSITIVITY)); + #endif + #endif + #if Z_SENSORLESS + stepperZ.homing_threshold(Z_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(Z2) + stepperZ2.homing_threshold(CAT(TERN(Z2_SENSORLESS, Z2, Z), _STALL_SENSITIVITY)); + #endif + #if AXIS_HAS_STALLGUARD(Z3) + stepperZ3.homing_threshold(CAT(TERN(Z3_SENSORLESS, Z3, Z), _STALL_SENSITIVITY)); + #endif + #if AXIS_HAS_STALLGUARD(Z4) + stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY)); + #endif + #endif #endif #ifdef TMC_ADV From 2107bc583626f4c28b6bda2c81140315b070ea09 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 1 May 2020 00:04:55 -0500 Subject: [PATCH 0352/1454] Clean up EEPROM interfaces (#17803) --- Marlin/src/HAL/DUE/eeprom_flash.cpp | 966 +++++++++++++++++- Marlin/src/HAL/DUE/eeprom_if_flash.cpp | 1006 ------------------- Marlin/src/HAL/LPC1768/eeprom_wired.cpp | 3 +- Marlin/src/HAL/STM32/eeprom_wired.cpp | 1 + Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp | 51 +- Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp | 2 +- Marlin/src/HAL/shared/eeprom_if_i2c.cpp | 20 +- Marlin/src/HAL/shared/eeprom_if_spi.cpp | 10 +- 8 files changed, 991 insertions(+), 1068 deletions(-) delete mode 100644 Marlin/src/HAL/DUE/eeprom_if_flash.cpp diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index 7076dd03db..c07d05adfc 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -26,35 +26,967 @@ #if ENABLED(FLASH_EEPROM_EMULATION) -#include "../../inc/MarlinConfig.h" - -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" - -#if !defined(E2END) - #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) +#ifndef E2END + #define E2END 0xFFF // Default to Flash emulated EEPROM size (eeprom_emul.cpp) #endif -extern void eeprom_flush(); +/* EEPROM emulation over flash with reduced wear + * + * We will use 2 contiguous groups of pages as main and alternate. + * We want an structure that allows to read as fast as possible, + * without the need of scanning the whole FLASH memory. + * + * FLASH bits default erased state is 1, and can be set to 0 + * on a per bit basis. To reset them to 1, a full page erase + * is needed. + * + * Values are stored as differences that should be applied to a + * completely erased EEPROM (filled with 0xFFs). We just encode + * the starting address of the values to change, the length of + * the block of new values, and the values themselves. All diffs + * are accumulated into a RAM buffer, compacted into the least + * amount of non overlapping diffs possible and sorted by starting + * address before being saved into the next available page of FLASH + * of the current group. + * Once the current group is completely full, we compact it and save + * it into the other group, then erase the current group and switch + * to that new group and set it as current. + * + * The FLASH endurance is about 1/10 ... 1/100 of an EEPROM + * endurance, but EEPROM endurance is specified per byte, not + * per page. We can't emulate EE endurance with FLASH for all + * bytes, but we can emulate endurance for a given percent of + * bytes. + * + */ -size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_start() { return true; } +//#define EE_EMU_DEBUG + +#define EEPROMSize 4096 +#define PagesPerGroup 128 +#define GroupCount 2 +#define PageSize 256u + + /* Flash storage */ +typedef struct FLASH_SECTOR { + uint8_t page[PageSize]; +} FLASH_SECTOR_T; + +#define PAGE_FILL \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF + +#define FLASH_INIT_FILL \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ + PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL + +/* This is the FLASH area used to emulate a 2Kbyte EEPROM -- We need this buffer aligned + to a 256 byte boundary. */ +static const uint8_t flashStorage[PagesPerGroup * GroupCount * PageSize] __attribute__ ((aligned (PageSize))) = { FLASH_INIT_FILL }; + +/* Get the address of an specific page */ +static const FLASH_SECTOR_T* getFlashStorage(int page) { + return (const FLASH_SECTOR_T*)&flashStorage[page*PageSize]; +} + +static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes + curPage = 0, // Current FLASH page inside the group + curGroup = 0xFF; // Current FLASH group + +#define DEBUG_OUT ENABLED(EE_EMU_DEBUG) +#include "../../core/debug_out.h" + +static void ee_Dump(const int page, const void* data) { + + #ifdef EE_EMU_DEBUG + + const uint8_t* c = (const uint8_t*) data; + char buffer[80]; + + sprintf_P(buffer, PSTR("Page: %d (0x%04x)\n"), page, page); + DEBUG_ECHO(buffer); + + char* p = &buffer[0]; + for (int i = 0; i< PageSize; ++i) { + if ((i & 0xF) == 0) p += sprintf_P(p, PSTR("%04x] "), i); + + p += sprintf_P(p, PSTR(" %02x"), c[i]); + if ((i & 0xF) == 0xF) { + *p++ = '\n'; + *p = 0; + DEBUG_ECHO(buffer); + p = &buffer[0]; + } + } + + #else + UNUSED(page); + UNUSED(data); + #endif +} + +/* Flash Writing Protection Key */ +#define FWP_KEY 0x5Au + +#if SAM4S_SERIES + #define EEFC_FCR_FCMD(value) \ + ((EEFC_FCR_FCMD_Msk & ((value) << EEFC_FCR_FCMD_Pos))) + #define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE | EEFC_FSR_FLERR) +#else + #define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE) +#endif + +/** + * Writes the contents of the specified page (no previous erase) + * @param page (page #) + * @param data (pointer to the data buffer) + */ +__attribute__ ((long_call, section (".ramfunc"))) +static bool ee_PageWrite(uint16_t page, const void* data) { + + uint16_t i; + uint32_t addrflash = uint32_t(getFlashStorage(page)); + + // Read the flash contents + uint32_t pageContents[PageSize>>2]; + memcpy(pageContents, (void*)addrflash, PageSize); + + // We ONLY want to toggle bits that have changed, and that have changed to 0. + // SAM3X8E tends to destroy contiguous bits if reprogrammed without erasing, so + // we try by all means to avoid this. That is why it says: "The Partial + // Programming mode works only with 128-bit (or higher) boundaries. It cannot + // be used with boundaries lower than 128 bits (8, 16 or 32-bit for example)." + // All bits that did not change, set them to 1. + for (i = 0; i > 2; i++) + pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i])); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM PageWrite ", page); + DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); + DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); + DEBUG_FLUSH(); + + // Get the page relative to the start of the EFC controller, and the EFC controller to use + Efc *efc; + uint16_t fpage; + if (addrflash >= IFLASH1_ADDR) { + efc = EFC1; + fpage = (addrflash - IFLASH1_ADDR) / IFLASH1_PAGE_SIZE; + } + else { + efc = EFC0; + fpage = (addrflash - IFLASH0_ADDR) / IFLASH0_PAGE_SIZE; + } + + // Get the page that must be unlocked, then locked + uint16_t lpage = fpage & (~((IFLASH0_LOCK_REGION_SIZE / IFLASH0_PAGE_SIZE) - 1)); + + // Disable all interrupts + __disable_irq(); + + // Get the FLASH wait states + uint32_t orgWS = (efc->EEFC_FMR & EEFC_FMR_FWS_Msk) >> EEFC_FMR_FWS_Pos; + + // Set wait states to 6 (SAM errata) + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(6); + + // Unlock the flash page + uint32_t status; + efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(lpage) | EEFC_FCR_FCMD(EFC_FCMD_CLB); + while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { + // force compiler to not optimize this -- NOPs don't work! + __asm__ __volatile__(""); + }; + + if ((status & EEFC_ERROR_FLAGS) != 0) { + + // Restore original wait states + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); + + // Reenable interrupts + __enable_irq(); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ", page); + return false; + } + + // Write page and lock: Writing 8-bit and 16-bit data is not allowed and may lead to unpredictable data corruption. + const uint32_t * aligned_src = (const uint32_t *) &pageContents[0]; /*data;*/ + uint32_t * p_aligned_dest = (uint32_t *) addrflash; + for (i = 0; i < (IFLASH0_PAGE_SIZE / sizeof(uint32_t)); ++i) { + *p_aligned_dest++ = *aligned_src++; + } + efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(fpage) | EEFC_FCR_FCMD(EFC_FCMD_WPL); + while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { + // force compiler to not optimize this -- NOPs don't work! + __asm__ __volatile__(""); + }; + + if ((status & EEFC_ERROR_FLAGS) != 0) { + + // Restore original wait states + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); + + // Reenable interrupts + __enable_irq(); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Write failure for page ", page); + + return false; + } + + // Restore original wait states + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); + + // Reenable interrupts + __enable_irq(); + + // Compare contents + if (memcmp(getFlashStorage(page),data,PageSize)) { + + #ifdef EE_EMU_DEBUG + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Verify Write failure for page ", page); + + ee_Dump( page, (uint32_t *)addrflash); + ee_Dump(-page, data); + + // Calculate count of changed bits + uint32_t* p1 = (uint32_t*)addrflash; + uint32_t* p2 = (uint32_t*)data; + int count = 0; + for (i =0; i> 2; i++) { + if (p1[i] != p2[i]) { + uint32_t delta = p1[i] ^ p2[i]; + while (delta) { + if ((delta&1) != 0) + count++; + delta >>= 1; + } + } + } + DEBUG_ECHOLNPAIR("--> Differing bits: ", count); + #endif + + return false; + } -bool PersistentStore::access_finish() { - eeprom_flush(); return true; } +/** + * Erases the contents of the specified page + * @param page (page #) + */ +__attribute__ ((long_call, section (".ramfunc"))) +static bool ee_PageErase(uint16_t page) { + + uint16_t i; + uint32_t addrflash = uint32_t(getFlashStorage(page)); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM PageErase ", page); + DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); + DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); + DEBUG_FLUSH(); + + // Get the page relative to the start of the EFC controller, and the EFC controller to use + Efc *efc; + uint16_t fpage; + if (addrflash >= IFLASH1_ADDR) { + efc = EFC1; + fpage = (addrflash - IFLASH1_ADDR) / IFLASH1_PAGE_SIZE; + } + else { + efc = EFC0; + fpage = (addrflash - IFLASH0_ADDR) / IFLASH0_PAGE_SIZE; + } + + // Get the page that must be unlocked, then locked + uint16_t lpage = fpage & (~((IFLASH0_LOCK_REGION_SIZE / IFLASH0_PAGE_SIZE) - 1)); + + // Disable all interrupts + __disable_irq(); + + // Get the FLASH wait states + uint32_t orgWS = (efc->EEFC_FMR & EEFC_FMR_FWS_Msk) >> EEFC_FMR_FWS_Pos; + + // Set wait states to 6 (SAM errata) + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(6); + + // Unlock the flash page + uint32_t status; + efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(lpage) | EEFC_FCR_FCMD(EFC_FCMD_CLB); + while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { + // force compiler to not optimize this -- NOPs don't work! + __asm__ __volatile__(""); + }; + if ((status & EEFC_ERROR_FLAGS) != 0) { + + // Restore original wait states + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); + + // Reenable interrupts + __enable_irq(); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ",page); + + return false; + } + + // Erase Write page and lock: Writing 8-bit and 16-bit data is not allowed and may lead to unpredictable data corruption. + uint32_t * p_aligned_dest = (uint32_t *) addrflash; + for (i = 0; i < (IFLASH0_PAGE_SIZE / sizeof(uint32_t)); ++i) { + *p_aligned_dest++ = 0xFFFFFFFF; + } + efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(fpage) | EEFC_FCR_FCMD(EFC_FCMD_EWPL); + while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { + // force compiler to not optimize this -- NOPs don't work! + __asm__ __volatile__(""); + }; + if ((status & EEFC_ERROR_FLAGS) != 0) { + + // Restore original wait states + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); + + // Reenable interrupts + __enable_irq(); + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Erase failure for page ",page); + + return false; + } + + // Restore original wait states + efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); + + // Reenable interrupts + __enable_irq(); + + // Check erase + uint32_t * aligned_src = (uint32_t *) addrflash; + for (i = 0; i < PageSize >> 2; i++) { + if (*aligned_src++ != 0xFFFFFFFF) { + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page); + ee_Dump(page, (uint32_t *)addrflash); + return false; + } + } + + return true; +} + +static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer=false) { + + uint32_t baddr; + uint32_t blen; + + // If we were requested an address outside of the emulated range, fail now + if (address >= EEPROMSize) + return false; + + // Check that the value is not contained in the RAM buffer + if (!excludeRAMBuffer) { + uint16_t i = 0; + while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + + // Get the address of the block + baddr = buffer[i] | (buffer[i + 1] << 8); + + // Get the length of the block + blen = buffer[i + 2]; + + // If we reach the end of the list, break loop + if (blen == 0xFF) + break; + + // Check if data is contained in this block + if (address >= baddr && + address < (baddr + blen)) { + + // Yes, it is contained. Return it! + return buffer[i + 3 + address - baddr]; + } + + // As blocks are always sorted, if the starting address of this block is higher + // than the address we are looking for, break loop now - We wont find the value + // associated to the address + if (baddr > address) + break; + + // Jump to the next block + i += 3 + blen; + } + } + + // It is NOT on the RAM buffer. It could be stored in FLASH. We are + // ensured on a given FLASH page, address contents are never repeated + // but on different pages, there is no such warranty, so we must go + // backwards from the last written FLASH page to the first one. + for (int page = curPage - 1; page >= 0; --page) { + + // Get a pointer to the flash page + uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); + + uint16_t i = 0; + while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + + // Get the address of the block + baddr = pflash[i] | (pflash[i + 1] << 8); + + // Get the length of the block + blen = pflash[i + 2]; + + // If we reach the end of the list, break loop + if (blen == 0xFF) + break; + + // Check if data is contained in this block + if (address >= baddr && address < (baddr + blen)) + return pflash[i + 3 + address - baddr]; // Yes, it is contained. Return it! + + // As blocks are always sorted, if the starting address of this block is higher + // than the address we are looking for, break loop now - We wont find the value + // associated to the address + if (baddr > address) break; + + // Jump to the next block + i += 3 + blen; + } + } + + // If reached here, value is not stored, so return its default value + return 0xFF; +} + +static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) { + uint32_t baddr, + blen, + nextAddr = 0xFFFF, + nextRange = 0; + + // Check that the value is not contained in the RAM buffer + if (!excludeRAMBuffer) { + uint16_t i = 0; + while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + + // Get the address of the block + baddr = buffer[i] | (buffer[i + 1] << 8); + + // Get the length of the block + blen = buffer[i + 2]; + + // If we reach the end of the list, break loop + if (blen == 0xFF) break; + + // Check if address and address + 1 is contained in this block + if (address >= baddr && address < (baddr + blen)) + return address | ((blen - address + baddr) << 16); // Yes, it is contained. Return it! + + // Otherwise, check if we can use it as a limit + if (baddr > address && baddr < nextAddr) { + nextAddr = baddr; + nextRange = blen; + } + + // As blocks are always sorted, if the starting address of this block is higher + // than the address we are looking for, break loop now - We wont find the value + // associated to the address + if (baddr > address) break; + + // Jump to the next block + i += 3 + blen; + } + } + + // It is NOT on the RAM buffer. It could be stored in FLASH. We are + // ensured on a given FLASH page, address contents are never repeated + // but on different pages, there is no such warranty, so we must go + // backwards from the last written FLASH page to the first one. + for (int page = curPage - 1; page >= 0; --page) { + + // Get a pointer to the flash page + uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); + + uint16_t i = 0; + while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + + // Get the address of the block + baddr = pflash[i] | (pflash[i + 1] << 8); + + // Get the length of the block + blen = pflash[i + 2]; + + // If we reach the end of the list, break loop + if (blen == 0xFF) break; + + // Check if data is contained in this block + if (address >= baddr && address < (baddr + blen)) + return address | ((blen - address + baddr) << 16); // Yes, it is contained. Return it! + + // Otherwise, check if we can use it as a limit + if (baddr > address && baddr < nextAddr) { + nextAddr = baddr; + nextRange = blen; + } + + // As blocks are always sorted, if the starting address of this block is higher + // than the address we are looking for, break loop now - We wont find the value + // associated to the address + if (baddr > address) break; + + // Jump to the next block + i += 3 + blen; + } + } + + // If reached here, we will return the next valid address + return nextAddr | (nextRange << 16); +} + +static bool ee_IsPageClean(int page) { + uint32_t* pflash = (uint32_t*) getFlashStorage(page); + for (uint16_t i = 0; i < (PageSize >> 2); ++i) + if (*pflash++ != 0xFFFFFFFF) return false; + return true; +} + +static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData=0xFF) { + + // Check if RAM buffer has something to be written + bool isEmpty = true; + uint32_t* p = (uint32_t*) &buffer[0]; + for (uint16_t j = 0; j < (PageSize >> 2); j++) { + if (*p++ != 0xFFFFFFFF) { + isEmpty = false; + break; + } + } + + // If something has to be written, do so! + if (!isEmpty) { + + // Write the current ram buffer into FLASH + ee_PageWrite(curPage + curGroup * PagesPerGroup, buffer); + + // Clear the RAM buffer + memset(buffer, 0xFF, sizeof(buffer)); + + // Increment the page to use the next time + ++curPage; + } + + // Did we reach the maximum count of available pages per group for storage ? + if (curPage < PagesPerGroup) { + + // Do we have an override address ? + if (overrideAddress < EEPROMSize) { + + // Yes, just store the value into the RAM buffer + buffer[0] = overrideAddress & 0xFF; + buffer[0 + 1] = (overrideAddress >> 8) & 0xFF; + buffer[0 + 2] = 1; + buffer[0 + 3] = overrideData; + } + + // Done! + return true; + } + + // We have no space left on the current group - We must compact the values + uint16_t i = 0; + + // Compute the next group to use + int curwPage = 0, curwGroup = curGroup + 1; + if (curwGroup >= GroupCount) curwGroup = 0; + + uint32_t rdAddr = 0; + do { + + // Get the next valid range + uint32_t addrRange = ee_GetAddrRange(rdAddr, true); + + // Make sure not to skip the override address, if specified + int rdRange; + if (overrideAddress < EEPROMSize && + rdAddr <= overrideAddress && + (addrRange & 0xFFFF) > overrideAddress) { + + rdAddr = overrideAddress; + rdRange = 1; + } + else { + rdAddr = addrRange & 0xFFFF; + rdRange = addrRange >> 16; + } + + // If no range, break loop + if (rdRange == 0) + break; + + do { + + // Get the value + uint8_t rdValue = overrideAddress == rdAddr ? overrideData : ee_Read(rdAddr, true); + + // Do not bother storing default values + if (rdValue != 0xFF) { + + // If we have room, add it to the buffer + if (buffer[i + 2] == 0xFF) { + + // Uninitialized buffer, just add it! + buffer[i] = rdAddr & 0xFF; + buffer[i + 1] = (rdAddr >> 8) & 0xFF; + buffer[i + 2] = 1; + buffer[i + 3] = rdValue; + + } + else { + // Buffer already has contents. Check if we can extend it + + // Get the address of the block + uint32_t baddr = buffer[i] | (buffer[i + 1] << 8); + + // Get the length of the block + uint32_t blen = buffer[i + 2]; + + // Can we expand it ? + if (rdAddr == (baddr + blen) && + i < (PageSize - 4) && /* This block has a chance to contain data AND */ + buffer[i + 2] < (PageSize - i - 3)) {/* There is room for this block to be expanded */ + + // Yes, do it + ++buffer[i + 2]; + + // And store the value + buffer[i + 3 + rdAddr - baddr] = rdValue; + + } + else { + + // No, we can't expand it - Skip the existing block + i += 3 + blen; + + // Can we create a new slot ? + if (i > (PageSize - 4)) { + + // Not enough space - Write the current buffer to FLASH + ee_PageWrite(curwPage + curwGroup * PagesPerGroup, buffer); + + // Advance write page (as we are compacting, should never overflow!) + ++curwPage; + + // Clear RAM buffer + memset(buffer, 0xFF, sizeof(buffer)); + + // Start fresh */ + i = 0; + } + + // Enough space, add the new block + buffer[i] = rdAddr & 0xFF; + buffer[i + 1] = (rdAddr >> 8) & 0xFF; + buffer[i + 2] = 1; + buffer[i + 3] = rdValue; + } + } + } + + // Go to the next address + ++rdAddr; + + // Repeat for bytes of this range + } while (--rdRange); + + // Repeat until we run out of ranges + } while (rdAddr < EEPROMSize); + + // We must erase the previous group, in preparation for the next swap + for (int page = 0; page < curPage; page++) { + ee_PageErase(page + curGroup * PagesPerGroup); + } + + // Finally, Now the active group is the created new group + curGroup = curwGroup; + curPage = curwPage; + + // Done! + return true; +} + +static bool ee_Write(uint32_t address, uint8_t data) { + + // If we were requested an address outside of the emulated range, fail now + if (address >= EEPROMSize) return false; + + // Lets check if we have a block with that data previously defined. Block + // start addresses are always sorted in ascending order + uint16_t i = 0; + while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + + // Get the address of the block + uint32_t baddr = buffer[i] | (buffer[i + 1] << 8); + + // Get the length of the block + uint32_t blen = buffer[i + 2]; + + // If we reach the end of the list, break loop + if (blen == 0xFF) + break; + + // Check if data is contained in this block + if (address >= baddr && + address < (baddr + blen)) { + + // Yes, it is contained. Just modify it + buffer[i + 3 + address - baddr] = data; + + // Done! + return true; + } + + // Maybe we could add it to the front or to the back + // of this block ? + if ((address + 1) == baddr || address == (baddr + blen)) { + + // Potentially, it could be done. But we must ensure there is room + // so we can expand the block. Lets find how much free space remains + uint32_t iend = i; + do { + uint32_t ln = buffer[iend + 2]; + if (ln == 0xFF) break; + iend += 3 + ln; + } while (iend <= (PageSize - 4)); /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + + // Here, inxt points to the first free address in the buffer. Do we have room ? + if (iend < PageSize) { + // Yes, at least a byte is free - We can expand the block + + // Do we have to insert at the beginning ? + if ((address + 1) == baddr) { + + // Insert at the beginning + + // Make room at the beginning for our byte + memmove(&buffer[i + 3 + 1], &buffer[i + 3], iend - i - 3); + + // Adjust the header and store the data + buffer[i] = address & 0xFF; + buffer[i + 1] = (address >> 8) & 0xFF; + buffer[i + 2]++; + buffer[i + 3] = data; + + } + else { + + // Insert at the end - There is a very interesting thing that could happen here: + // Maybe we could coalesce the next block with this block. Let's try to do it! + uint16_t inext = i + 3 + blen; + if (inext <= (PageSize - 4) && + (buffer[inext] | uint16_t(buffer[inext + 1] << 8)) == (baddr + blen + 1)) { + // YES! ... we can coalesce blocks! . Do it! + + // Adjust this block header to include the next one + buffer[i + 2] += buffer[inext + 2] + 1; + + // Store data at the right place + buffer[i + 3 + blen] = data; + + // Remove the next block header and append its data + memmove(&buffer[inext + 1], &buffer[inext + 3], iend - inext - 3); + + // Finally, as we have saved 2 bytes at the end, make sure to clean them + buffer[iend - 2] = 0xFF; + buffer[iend - 1] = 0xFF; + + } + else { + // NO ... No coalescing possible yet + + // Make room at the end for our byte + memmove(&buffer[i + 3 + blen + 1], &buffer[i + 3 + blen], iend - i - 3 - blen); + + // And add the data to the block + buffer[i + 2]++; + buffer[i + 3 + blen] = data; + } + } + + // Done! + return true; + } + } + + // As blocks are always sorted, if the starting address of this block is higher + // than the address we are looking for, break loop now - We wont find the value + // associated to the address + if (baddr > address) break; + + // Jump to the next block + i += 3 + blen; + } + + // Value is not stored AND we can't expand previous block to contain it. We must create a new block + + // First, lets find how much free space remains + uint32_t iend = i; + while (iend <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ + uint32_t ln = buffer[iend + 2]; + if (ln == 0xFF) break; + iend += 3 + ln; + } + + // If there is room for a new block, insert it at the proper place + if (iend <= (PageSize - 4)) { + + // We have room to create a new block. Do so --- But add + // the block at the proper position, sorted by starting + // address, so it will be possible to compact it with other blocks. + + // Make space + memmove(&buffer[i + 4], &buffer[i], iend - i); + + // And add the block + buffer[i] = address & 0xFF; + buffer[i + 1] = (address >> 8) & 0xFF; + buffer[i + 2] = 1; + buffer[i + 3] = data; + + // Done! + return true; + } + + // Not enough room to store this information on this FLASH page - Perform a + // flush and override the address with the specified contents + return ee_Flush(address, data); +} + +static void ee_Init() { + + // Just init once! + if (curGroup != 0xFF) return; + + // Clean up the SRAM buffer + memset(buffer, 0xFF, sizeof(buffer)); + + // Now, we must find out the group where settings are stored + for (curGroup = 0; curGroup < GroupCount; curGroup++) + if (!ee_IsPageClean(curGroup * PagesPerGroup)) break; + + // If all groups seem to be used, default to first group + if (curGroup >= GroupCount) curGroup = 0; + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Current Group: ",curGroup); + DEBUG_FLUSH(); + + // Now, validate that all the other group pages are empty + for (int grp = 0; grp < GroupCount; grp++) { + if (grp == curGroup) continue; + + for (int page = 0; page < PagesPerGroup; page++) { + if (!ee_IsPageClean(grp * PagesPerGroup + page)) { + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp); + DEBUG_FLUSH(); + ee_PageErase(grp * PagesPerGroup + page); + } + } + } + + // Finally, for the active group, determine the first unused page + // and also validate that all the other ones are clean + for (curPage = 0; curPage < PagesPerGroup; curPage++) { + if (ee_IsPageClean(curGroup * PagesPerGroup + curPage)) { + ee_Dump(curGroup * PagesPerGroup + curPage, getFlashStorage(curGroup * PagesPerGroup + curPage)); + break; + } + } + + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Active page: ", curPage); + DEBUG_FLUSH(); + + // Make sure the pages following the first clean one are also clean + for (int page = curPage + 1; page < PagesPerGroup; page++) { + if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) { + DEBUG_ECHO_START(); + DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup); + DEBUG_FLUSH(); + ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page)); + ee_PageErase(curGroup * PagesPerGroup + page); + } + } +} + +/* PersistentStore -----------------------------------------------------------*/ + +#include "../shared/eeprom_api.h" + +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_start() { ee_Init(); return true; } +bool PersistentStore::access_finish() { ee_Flush(); return true; } + bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t * const p = (uint8_t * const)pos; uint8_t v = *value; // EEPROM has only ~100,000 write cycles, // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { - eeprom_write_byte(p, v); + if (v != ee_Read(uint32_t(p))) { + ee_Write(uint32_t(p), v); delay(2); - if (eeprom_read_byte(p) != v) { + if (ee_Read(uint32_t(p)) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; } @@ -68,7 +1000,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + uint8_t c = ee_Read(uint32_t(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; @@ -77,5 +1009,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -#endif // EEPROM_SETTINGS +#endif // FLASH_EEPROM_EMULATION #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/eeprom_if_flash.cpp b/Marlin/src/HAL/DUE/eeprom_if_flash.cpp deleted file mode 100644 index f91bfda668..0000000000 --- a/Marlin/src/HAL/DUE/eeprom_if_flash.cpp +++ /dev/null @@ -1,1006 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#ifdef ARDUINO_ARCH_SAM - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - -#include "../shared/Marduino.h" -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" - -/* EEPROM emulation over flash with reduced wear - * - * We will use 2 contiguous groups of pages as main and alternate. - * We want an structure that allows to read as fast as possible, - * without the need of scanning the whole FLASH memory. - * - * FLASH bits default erased state is 1, and can be set to 0 - * on a per bit basis. To reset them to 1, a full page erase - * is needed. - * - * Values are stored as differences that should be applied to a - * completely erased EEPROM (filled with 0xFFs). We just encode - * the starting address of the values to change, the length of - * the block of new values, and the values themselves. All diffs - * are accumulated into a RAM buffer, compacted into the least - * amount of non overlapping diffs possible and sorted by starting - * address before being saved into the next available page of FLASH - * of the current group. - * Once the current group is completely full, we compact it and save - * it into the other group, then erase the current group and switch - * to that new group and set it as current. - * - * The FLASH endurance is about 1/10 ... 1/100 of an EEPROM - * endurance, but EEPROM endurance is specified per byte, not - * per page. We can't emulate EE endurance with FLASH for all - * bytes, but we can emulate endurance for a given percent of - * bytes. - * - */ - -//#define EE_EMU_DEBUG - -#define EEPROMSize 4096 -#define PagesPerGroup 128 -#define GroupCount 2 -#define PageSize 256u - - /* Flash storage */ -typedef struct FLASH_SECTOR { - uint8_t page[PageSize]; -} FLASH_SECTOR_T; - -#define PAGE_FILL \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, \ - 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF - -#define FLASH_INIT_FILL \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL, \ - PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL,PAGE_FILL - -/* This is the FLASH area used to emulate a 2Kbyte EEPROM -- We need this buffer aligned - to a 256 byte boundary. */ -static const uint8_t flashStorage[PagesPerGroup * GroupCount * PageSize] __attribute__ ((aligned (PageSize))) = { FLASH_INIT_FILL }; - -/* Get the address of an specific page */ -static const FLASH_SECTOR_T* getFlashStorage(int page) { - return (const FLASH_SECTOR_T*)&flashStorage[page*PageSize]; -} - -static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes - curPage = 0, // Current FLASH page inside the group - curGroup = 0xFF; // Current FLASH group - -#define DEBUG_OUT ENABLED(EE_EMU_DEBUG) -#include "../../core/debug_out.h" - -static void ee_Dump(const int page, const void* data) { - - #ifdef EE_EMU_DEBUG - - const uint8_t* c = (const uint8_t*) data; - char buffer[80]; - - sprintf_P(buffer, PSTR("Page: %d (0x%04x)\n"), page, page); - DEBUG_ECHO(buffer); - - char* p = &buffer[0]; - for (int i = 0; i< PageSize; ++i) { - if ((i & 0xF) == 0) p += sprintf_P(p, PSTR("%04x] "), i); - - p += sprintf_P(p, PSTR(" %02x"), c[i]); - if ((i & 0xF) == 0xF) { - *p++ = '\n'; - *p = 0; - DEBUG_ECHO(buffer); - p = &buffer[0]; - } - } - - #else - UNUSED(page); - UNUSED(data); - #endif -} - -/* Flash Writing Protection Key */ -#define FWP_KEY 0x5Au - -#if SAM4S_SERIES - #define EEFC_FCR_FCMD(value) \ - ((EEFC_FCR_FCMD_Msk & ((value) << EEFC_FCR_FCMD_Pos))) - #define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE | EEFC_FSR_FLERR) -#else - #define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE) -#endif - -/** - * Writes the contents of the specified page (no previous erase) - * @param page (page #) - * @param data (pointer to the data buffer) - */ -__attribute__ ((long_call, section (".ramfunc"))) -static bool ee_PageWrite(uint16_t page, const void* data) { - - uint16_t i; - uint32_t addrflash = uint32_t(getFlashStorage(page)); - - // Read the flash contents - uint32_t pageContents[PageSize>>2]; - memcpy(pageContents, (void*)addrflash, PageSize); - - // We ONLY want to toggle bits that have changed, and that have changed to 0. - // SAM3X8E tends to destroy contiguous bits if reprogrammed without erasing, so - // we try by all means to avoid this. That is why it says: "The Partial - // Programming mode works only with 128-bit (or higher) boundaries. It cannot - // be used with boundaries lower than 128 bits (8, 16 or 32-bit for example)." - // All bits that did not change, set them to 1. - for (i = 0; i > 2; i++) - pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i])); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM PageWrite ", page); - DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); - DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); - DEBUG_FLUSH(); - - // Get the page relative to the start of the EFC controller, and the EFC controller to use - Efc *efc; - uint16_t fpage; - if (addrflash >= IFLASH1_ADDR) { - efc = EFC1; - fpage = (addrflash - IFLASH1_ADDR) / IFLASH1_PAGE_SIZE; - } - else { - efc = EFC0; - fpage = (addrflash - IFLASH0_ADDR) / IFLASH0_PAGE_SIZE; - } - - // Get the page that must be unlocked, then locked - uint16_t lpage = fpage & (~((IFLASH0_LOCK_REGION_SIZE / IFLASH0_PAGE_SIZE) - 1)); - - // Disable all interrupts - __disable_irq(); - - // Get the FLASH wait states - uint32_t orgWS = (efc->EEFC_FMR & EEFC_FMR_FWS_Msk) >> EEFC_FMR_FWS_Pos; - - // Set wait states to 6 (SAM errata) - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(6); - - // Unlock the flash page - uint32_t status; - efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(lpage) | EEFC_FCR_FCMD(EFC_FCMD_CLB); - while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { - // force compiler to not optimize this -- NOPs don't work! - __asm__ __volatile__(""); - }; - - if ((status & EEFC_ERROR_FLAGS) != 0) { - - // Restore original wait states - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); - - // Reenable interrupts - __enable_irq(); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ", page); - return false; - } - - // Write page and lock: Writing 8-bit and 16-bit data is not allowed and may lead to unpredictable data corruption. - const uint32_t * aligned_src = (const uint32_t *) &pageContents[0]; /*data;*/ - uint32_t * p_aligned_dest = (uint32_t *) addrflash; - for (i = 0; i < (IFLASH0_PAGE_SIZE / sizeof(uint32_t)); ++i) { - *p_aligned_dest++ = *aligned_src++; - } - efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(fpage) | EEFC_FCR_FCMD(EFC_FCMD_WPL); - while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { - // force compiler to not optimize this -- NOPs don't work! - __asm__ __volatile__(""); - }; - - if ((status & EEFC_ERROR_FLAGS) != 0) { - - // Restore original wait states - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); - - // Reenable interrupts - __enable_irq(); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Write failure for page ", page); - - return false; - } - - // Restore original wait states - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); - - // Reenable interrupts - __enable_irq(); - - // Compare contents - if (memcmp(getFlashStorage(page),data,PageSize)) { - - #ifdef EE_EMU_DEBUG - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Verify Write failure for page ", page); - - ee_Dump( page, (uint32_t *)addrflash); - ee_Dump(-page, data); - - // Calculate count of changed bits - uint32_t* p1 = (uint32_t*)addrflash; - uint32_t* p2 = (uint32_t*)data; - int count = 0; - for (i =0; i> 2; i++) { - if (p1[i] != p2[i]) { - uint32_t delta = p1[i] ^ p2[i]; - while (delta) { - if ((delta&1) != 0) - count++; - delta >>= 1; - } - } - } - DEBUG_ECHOLNPAIR("--> Differing bits: ", count); - #endif - - return false; - } - - return true; -} - -/** - * Erases the contents of the specified page - * @param page (page #) - */ -__attribute__ ((long_call, section (".ramfunc"))) -static bool ee_PageErase(uint16_t page) { - - uint16_t i; - uint32_t addrflash = uint32_t(getFlashStorage(page)); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM PageErase ", page); - DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); - DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); - DEBUG_FLUSH(); - - // Get the page relative to the start of the EFC controller, and the EFC controller to use - Efc *efc; - uint16_t fpage; - if (addrflash >= IFLASH1_ADDR) { - efc = EFC1; - fpage = (addrflash - IFLASH1_ADDR) / IFLASH1_PAGE_SIZE; - } - else { - efc = EFC0; - fpage = (addrflash - IFLASH0_ADDR) / IFLASH0_PAGE_SIZE; - } - - // Get the page that must be unlocked, then locked - uint16_t lpage = fpage & (~((IFLASH0_LOCK_REGION_SIZE / IFLASH0_PAGE_SIZE) - 1)); - - // Disable all interrupts - __disable_irq(); - - // Get the FLASH wait states - uint32_t orgWS = (efc->EEFC_FMR & EEFC_FMR_FWS_Msk) >> EEFC_FMR_FWS_Pos; - - // Set wait states to 6 (SAM errata) - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(6); - - // Unlock the flash page - uint32_t status; - efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(lpage) | EEFC_FCR_FCMD(EFC_FCMD_CLB); - while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { - // force compiler to not optimize this -- NOPs don't work! - __asm__ __volatile__(""); - }; - if ((status & EEFC_ERROR_FLAGS) != 0) { - - // Restore original wait states - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); - - // Reenable interrupts - __enable_irq(); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ",page); - - return false; - } - - // Erase Write page and lock: Writing 8-bit and 16-bit data is not allowed and may lead to unpredictable data corruption. - uint32_t * p_aligned_dest = (uint32_t *) addrflash; - for (i = 0; i < (IFLASH0_PAGE_SIZE / sizeof(uint32_t)); ++i) { - *p_aligned_dest++ = 0xFFFFFFFF; - } - efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(fpage) | EEFC_FCR_FCMD(EFC_FCMD_EWPL); - while (((status = efc->EEFC_FSR) & EEFC_FSR_FRDY) != EEFC_FSR_FRDY) { - // force compiler to not optimize this -- NOPs don't work! - __asm__ __volatile__(""); - }; - if ((status & EEFC_ERROR_FLAGS) != 0) { - - // Restore original wait states - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); - - // Reenable interrupts - __enable_irq(); - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Erase failure for page ",page); - - return false; - } - - // Restore original wait states - efc->EEFC_FMR = (efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk)) | EEFC_FMR_FWS(orgWS); - - // Reenable interrupts - __enable_irq(); - - // Check erase - uint32_t * aligned_src = (uint32_t *) addrflash; - for (i = 0; i < PageSize >> 2; i++) { - if (*aligned_src++ != 0xFFFFFFFF) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page); - ee_Dump(page, (uint32_t *)addrflash); - return false; - } - } - - return true; -} - -static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer=false) { - - uint32_t baddr; - uint32_t blen; - - // If we were requested an address outside of the emulated range, fail now - if (address >= EEPROMSize) - return false; - - // Check that the value is not contained in the RAM buffer - if (!excludeRAMBuffer) { - uint16_t i = 0; - while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - - // Get the address of the block - baddr = buffer[i] | (buffer[i + 1] << 8); - - // Get the length of the block - blen = buffer[i + 2]; - - // If we reach the end of the list, break loop - if (blen == 0xFF) - break; - - // Check if data is contained in this block - if (address >= baddr && - address < (baddr + blen)) { - - // Yes, it is contained. Return it! - return buffer[i + 3 + address - baddr]; - } - - // As blocks are always sorted, if the starting address of this block is higher - // than the address we are looking for, break loop now - We wont find the value - // associated to the address - if (baddr > address) - break; - - // Jump to the next block - i += 3 + blen; - } - } - - // It is NOT on the RAM buffer. It could be stored in FLASH. We are - // ensured on a given FLASH page, address contents are never repeated - // but on different pages, there is no such warranty, so we must go - // backwards from the last written FLASH page to the first one. - for (int page = curPage - 1; page >= 0; --page) { - - // Get a pointer to the flash page - uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); - - uint16_t i = 0; - while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - - // Get the address of the block - baddr = pflash[i] | (pflash[i + 1] << 8); - - // Get the length of the block - blen = pflash[i + 2]; - - // If we reach the end of the list, break loop - if (blen == 0xFF) - break; - - // Check if data is contained in this block - if (address >= baddr && address < (baddr + blen)) - return pflash[i + 3 + address - baddr]; // Yes, it is contained. Return it! - - // As blocks are always sorted, if the starting address of this block is higher - // than the address we are looking for, break loop now - We wont find the value - // associated to the address - if (baddr > address) break; - - // Jump to the next block - i += 3 + blen; - } - } - - // If reached here, value is not stored, so return its default value - return 0xFF; -} - -static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) { - uint32_t baddr, - blen, - nextAddr = 0xFFFF, - nextRange = 0; - - // Check that the value is not contained in the RAM buffer - if (!excludeRAMBuffer) { - uint16_t i = 0; - while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - - // Get the address of the block - baddr = buffer[i] | (buffer[i + 1] << 8); - - // Get the length of the block - blen = buffer[i + 2]; - - // If we reach the end of the list, break loop - if (blen == 0xFF) break; - - // Check if address and address + 1 is contained in this block - if (address >= baddr && address < (baddr + blen)) - return address | ((blen - address + baddr) << 16); // Yes, it is contained. Return it! - - // Otherwise, check if we can use it as a limit - if (baddr > address && baddr < nextAddr) { - nextAddr = baddr; - nextRange = blen; - } - - // As blocks are always sorted, if the starting address of this block is higher - // than the address we are looking for, break loop now - We wont find the value - // associated to the address - if (baddr > address) break; - - // Jump to the next block - i += 3 + blen; - } - } - - // It is NOT on the RAM buffer. It could be stored in FLASH. We are - // ensured on a given FLASH page, address contents are never repeated - // but on different pages, there is no such warranty, so we must go - // backwards from the last written FLASH page to the first one. - for (int page = curPage - 1; page >= 0; --page) { - - // Get a pointer to the flash page - uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup); - - uint16_t i = 0; - while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - - // Get the address of the block - baddr = pflash[i] | (pflash[i + 1] << 8); - - // Get the length of the block - blen = pflash[i + 2]; - - // If we reach the end of the list, break loop - if (blen == 0xFF) break; - - // Check if data is contained in this block - if (address >= baddr && address < (baddr + blen)) - return address | ((blen - address + baddr) << 16); // Yes, it is contained. Return it! - - // Otherwise, check if we can use it as a limit - if (baddr > address && baddr < nextAddr) { - nextAddr = baddr; - nextRange = blen; - } - - // As blocks are always sorted, if the starting address of this block is higher - // than the address we are looking for, break loop now - We wont find the value - // associated to the address - if (baddr > address) break; - - // Jump to the next block - i += 3 + blen; - } - } - - // If reached here, we will return the next valid address - return nextAddr | (nextRange << 16); -} - -static bool ee_IsPageClean(int page) { - uint32_t* pflash = (uint32_t*) getFlashStorage(page); - for (uint16_t i = 0; i < (PageSize >> 2); ++i) - if (*pflash++ != 0xFFFFFFFF) return false; - return true; -} - -static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData=0xFF) { - - // Check if RAM buffer has something to be written - bool isEmpty = true; - uint32_t* p = (uint32_t*) &buffer[0]; - for (uint16_t j = 0; j < (PageSize >> 2); j++) { - if (*p++ != 0xFFFFFFFF) { - isEmpty = false; - break; - } - } - - // If something has to be written, do so! - if (!isEmpty) { - - // Write the current ram buffer into FLASH - ee_PageWrite(curPage + curGroup * PagesPerGroup, buffer); - - // Clear the RAM buffer - memset(buffer, 0xFF, sizeof(buffer)); - - // Increment the page to use the next time - ++curPage; - } - - // Did we reach the maximum count of available pages per group for storage ? - if (curPage < PagesPerGroup) { - - // Do we have an override address ? - if (overrideAddress < EEPROMSize) { - - // Yes, just store the value into the RAM buffer - buffer[0] = overrideAddress & 0xFF; - buffer[0 + 1] = (overrideAddress >> 8) & 0xFF; - buffer[0 + 2] = 1; - buffer[0 + 3] = overrideData; - } - - // Done! - return true; - } - - // We have no space left on the current group - We must compact the values - uint16_t i = 0; - - // Compute the next group to use - int curwPage = 0, curwGroup = curGroup + 1; - if (curwGroup >= GroupCount) curwGroup = 0; - - uint32_t rdAddr = 0; - do { - - // Get the next valid range - uint32_t addrRange = ee_GetAddrRange(rdAddr, true); - - // Make sure not to skip the override address, if specified - int rdRange; - if (overrideAddress < EEPROMSize && - rdAddr <= overrideAddress && - (addrRange & 0xFFFF) > overrideAddress) { - - rdAddr = overrideAddress; - rdRange = 1; - } - else { - rdAddr = addrRange & 0xFFFF; - rdRange = addrRange >> 16; - } - - // If no range, break loop - if (rdRange == 0) - break; - - do { - - // Get the value - uint8_t rdValue = overrideAddress == rdAddr ? overrideData : ee_Read(rdAddr, true); - - // Do not bother storing default values - if (rdValue != 0xFF) { - - // If we have room, add it to the buffer - if (buffer[i + 2] == 0xFF) { - - // Uninitialized buffer, just add it! - buffer[i] = rdAddr & 0xFF; - buffer[i + 1] = (rdAddr >> 8) & 0xFF; - buffer[i + 2] = 1; - buffer[i + 3] = rdValue; - - } - else { - // Buffer already has contents. Check if we can extend it - - // Get the address of the block - uint32_t baddr = buffer[i] | (buffer[i + 1] << 8); - - // Get the length of the block - uint32_t blen = buffer[i + 2]; - - // Can we expand it ? - if (rdAddr == (baddr + blen) && - i < (PageSize - 4) && /* This block has a chance to contain data AND */ - buffer[i + 2] < (PageSize - i - 3)) {/* There is room for this block to be expanded */ - - // Yes, do it - ++buffer[i + 2]; - - // And store the value - buffer[i + 3 + rdAddr - baddr] = rdValue; - - } - else { - - // No, we can't expand it - Skip the existing block - i += 3 + blen; - - // Can we create a new slot ? - if (i > (PageSize - 4)) { - - // Not enough space - Write the current buffer to FLASH - ee_PageWrite(curwPage + curwGroup * PagesPerGroup, buffer); - - // Advance write page (as we are compacting, should never overflow!) - ++curwPage; - - // Clear RAM buffer - memset(buffer, 0xFF, sizeof(buffer)); - - // Start fresh */ - i = 0; - } - - // Enough space, add the new block - buffer[i] = rdAddr & 0xFF; - buffer[i + 1] = (rdAddr >> 8) & 0xFF; - buffer[i + 2] = 1; - buffer[i + 3] = rdValue; - } - } - } - - // Go to the next address - ++rdAddr; - - // Repeat for bytes of this range - } while (--rdRange); - - // Repeat until we run out of ranges - } while (rdAddr < EEPROMSize); - - // We must erase the previous group, in preparation for the next swap - for (int page = 0; page < curPage; page++) { - ee_PageErase(page + curGroup * PagesPerGroup); - } - - // Finally, Now the active group is the created new group - curGroup = curwGroup; - curPage = curwPage; - - // Done! - return true; -} - -static bool ee_Write(uint32_t address, uint8_t data) { - - // If we were requested an address outside of the emulated range, fail now - if (address >= EEPROMSize) return false; - - // Lets check if we have a block with that data previously defined. Block - // start addresses are always sorted in ascending order - uint16_t i = 0; - while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - - // Get the address of the block - uint32_t baddr = buffer[i] | (buffer[i + 1] << 8); - - // Get the length of the block - uint32_t blen = buffer[i + 2]; - - // If we reach the end of the list, break loop - if (blen == 0xFF) - break; - - // Check if data is contained in this block - if (address >= baddr && - address < (baddr + blen)) { - - // Yes, it is contained. Just modify it - buffer[i + 3 + address - baddr] = data; - - // Done! - return true; - } - - // Maybe we could add it to the front or to the back - // of this block ? - if ((address + 1) == baddr || address == (baddr + blen)) { - - // Potentially, it could be done. But we must ensure there is room - // so we can expand the block. Lets find how much free space remains - uint32_t iend = i; - do { - uint32_t ln = buffer[iend + 2]; - if (ln == 0xFF) break; - iend += 3 + ln; - } while (iend <= (PageSize - 4)); /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - - // Here, inxt points to the first free address in the buffer. Do we have room ? - if (iend < PageSize) { - // Yes, at least a byte is free - We can expand the block - - // Do we have to insert at the beginning ? - if ((address + 1) == baddr) { - - // Insert at the beginning - - // Make room at the beginning for our byte - memmove(&buffer[i + 3 + 1], &buffer[i + 3], iend - i - 3); - - // Adjust the header and store the data - buffer[i] = address & 0xFF; - buffer[i + 1] = (address >> 8) & 0xFF; - buffer[i + 2]++; - buffer[i + 3] = data; - - } - else { - - // Insert at the end - There is a very interesting thing that could happen here: - // Maybe we could coalesce the next block with this block. Let's try to do it! - uint16_t inext = i + 3 + blen; - if (inext <= (PageSize - 4) && - (buffer[inext] | uint16_t(buffer[inext + 1] << 8)) == (baddr + blen + 1)) { - // YES! ... we can coalesce blocks! . Do it! - - // Adjust this block header to include the next one - buffer[i + 2] += buffer[inext + 2] + 1; - - // Store data at the right place - buffer[i + 3 + blen] = data; - - // Remove the next block header and append its data - memmove(&buffer[inext + 1], &buffer[inext + 3], iend - inext - 3); - - // Finally, as we have saved 2 bytes at the end, make sure to clean them - buffer[iend - 2] = 0xFF; - buffer[iend - 1] = 0xFF; - - } - else { - // NO ... No coalescing possible yet - - // Make room at the end for our byte - memmove(&buffer[i + 3 + blen + 1], &buffer[i + 3 + blen], iend - i - 3 - blen); - - // And add the data to the block - buffer[i + 2]++; - buffer[i + 3 + blen] = data; - } - } - - // Done! - return true; - } - } - - // As blocks are always sorted, if the starting address of this block is higher - // than the address we are looking for, break loop now - We wont find the value - // associated to the address - if (baddr > address) break; - - // Jump to the next block - i += 3 + blen; - } - - // Value is not stored AND we can't expand previous block to contain it. We must create a new block - - // First, lets find how much free space remains - uint32_t iend = i; - while (iend <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */ - uint32_t ln = buffer[iend + 2]; - if (ln == 0xFF) break; - iend += 3 + ln; - } - - // If there is room for a new block, insert it at the proper place - if (iend <= (PageSize - 4)) { - - // We have room to create a new block. Do so --- But add - // the block at the proper position, sorted by starting - // address, so it will be possible to compact it with other blocks. - - // Make space - memmove(&buffer[i + 4], &buffer[i], iend - i); - - // And add the block - buffer[i] = address & 0xFF; - buffer[i + 1] = (address >> 8) & 0xFF; - buffer[i + 2] = 1; - buffer[i + 3] = data; - - // Done! - return true; - } - - // Not enough room to store this information on this FLASH page - Perform a - // flush and override the address with the specified contents - return ee_Flush(address, data); -} - -static void ee_Init() { - - // Just init once! - if (curGroup != 0xFF) return; - - // Clean up the SRAM buffer - memset(buffer, 0xFF, sizeof(buffer)); - - // Now, we must find out the group where settings are stored - for (curGroup = 0; curGroup < GroupCount; curGroup++) - if (!ee_IsPageClean(curGroup * PagesPerGroup)) break; - - // If all groups seem to be used, default to first group - if (curGroup >= GroupCount) curGroup = 0; - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Current Group: ",curGroup); - DEBUG_FLUSH(); - - // Now, validate that all the other group pages are empty - for (int grp = 0; grp < GroupCount; grp++) { - if (grp == curGroup) continue; - - for (int page = 0; page < PagesPerGroup; page++) { - if (!ee_IsPageClean(grp * PagesPerGroup + page)) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp); - DEBUG_FLUSH(); - ee_PageErase(grp * PagesPerGroup + page); - } - } - } - - // Finally, for the active group, determine the first unused page - // and also validate that all the other ones are clean - for (curPage = 0; curPage < PagesPerGroup; curPage++) { - if (ee_IsPageClean(curGroup * PagesPerGroup + curPage)) { - ee_Dump(curGroup * PagesPerGroup + curPage, getFlashStorage(curGroup * PagesPerGroup + curPage)); - break; - } - } - - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Active page: ", curPage); - DEBUG_FLUSH(); - - // Make sure the pages following the first clean one are also clean - for (int page = curPage + 1; page < PagesPerGroup; page++) { - if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup); - DEBUG_FLUSH(); - ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page)); - ee_PageErase(curGroup * PagesPerGroup + page); - } - } -} - -uint8_t eeprom_read_byte(uint8_t* addr) { - ee_Init(); - return ee_Read((uint32_t)addr); -} - -void eeprom_write_byte(uint8_t* addr, uint8_t value) { - ee_Init(); - ee_Write((uint32_t)addr, value); -} - -void eeprom_update_block(const void *__src, void *__dst, size_t __n) { - uint8_t* dst = (uint8_t*)__dst; - const uint8_t* src = (const uint8_t*)__src; - while (__n--) { - eeprom_write_byte(dst, *src); - ++dst; - ++src; - } -} - -void eeprom_read_block(void *__dst, const void *__src, size_t __n) { - uint8_t* dst = (uint8_t*)__dst; - uint8_t* src = (uint8_t*)__src; - while (__n--) { - *dst = eeprom_read_byte(src); - ++dst; - ++src; - } -} - -void eeprom_flush() { - ee_Flush(); -} - -#endif // FLASH_EEPROM_EMULATION -#endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index 677138c688..255ff6faad 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -30,6 +30,7 @@ * with implementations supplied by the framework. */ +#include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" #ifndef EEPROM_SIZE @@ -40,7 +41,7 @@ size_t PersistentStore::capacity() { return EEPROM_SIZE; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { - TERN_(I2C_EEPROM, eeprom_init()); + eeprom_init(); return true; } diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index 5639e532cc..084b9e6eab 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -38,6 +38,7 @@ size_t PersistentStore::capacity() { return E2END + 1; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { + eeprom_init(); return true; } diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp index cd5648c73a..85503a56e5 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp @@ -34,7 +34,28 @@ //#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR #endif -void ee_init() { +void ee_write_byte(uint8_t *pos, unsigned char value) { + HAL_FLASH_Unlock(); + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); + + const unsigned eeprom_address = (unsigned)pos; + if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK) + for (;;) HAL_Delay(1); // Spin forever until watchdog reset + + HAL_FLASH_Lock(); +} + +uint8_t ee_read_byte(uint8_t *pos) { + uint16_t data = 0xFF; + const unsigned eeprom_address = (unsigned)pos; + (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error + return uint8_t(data); +} + +size_t PersistentStore::capacity() { return E2END + 1; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::access_start() { static bool ee_initialized = false; if (!ee_initialized) { HAL_FLASH_Unlock(); @@ -48,35 +69,9 @@ void ee_init() { HAL_FLASH_Lock(); ee_initialized = true; } + return true; } -void ee_write_byte(uint8_t *pos, unsigned char value) { - ee_init(); - - HAL_FLASH_Unlock(); - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - - const unsigned eeprom_address = (unsigned)pos; - if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK) - for (;;) HAL_Delay(1); // Spin forever until watchdog reset - - HAL_FLASH_Lock(); -} - -uint8_t ee_read_byte(uint8_t *pos) { - ee_init(); - - uint16_t data = 0xFF; - const unsigned eeprom_address = (unsigned)pos; - (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error - - return uint8_t(data); -} - -size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_start() { return true; } -bool PersistentStore::access_finish() { return true; } - bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t * const p = (uint8_t * const)pos; diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp index 7eb06ebdde..08c3c30528 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp @@ -35,10 +35,10 @@ #include "../shared/eeprom_api.h" size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { + eeprom_init(); return true; } diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index 0f429b7c67..d6f1bad85f 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -27,21 +27,18 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(USE_SHARED_EEPROM, I2C_EEPROM) - -#include "../HAL.h" -#include +#if ENABLED(I2C_EEPROM) #include "eeprom_if.h" +#include + +void eeprom_init() { Wire.begin(); } + +#if ENABLED(USE_SHARED_EEPROM) #ifndef EEPROM_WRITE_DELAY #define EEPROM_WRITE_DELAY 5 #endif - -// ------------------------ -// Private Variables -// ------------------------ - #ifndef EEPROM_DEVICE_ADDRESS #define EEPROM_DEVICE_ADDRESS 0x50 #endif @@ -52,8 +49,6 @@ static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRE // Public functions // ------------------------ -void eeprom_init() { Wire.begin(); } - void eeprom_write_byte(uint8_t *pos, unsigned char value) { const unsigned eeprom_address = (unsigned)pos; @@ -79,4 +74,5 @@ uint8_t eeprom_read_byte(uint8_t *pos) { return Wire.available() ? Wire.read() : 0xFF; } -#endif // USE_SHARED_EEPROM && I2C_EEPROM +#endif // USE_SHARED_EEPROM +#endif // I2C_EEPROM diff --git a/Marlin/src/HAL/shared/eeprom_if_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp index 6a3c5cc059..88dbf97b5d 100644 --- a/Marlin/src/HAL/shared/eeprom_if_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp @@ -27,11 +27,14 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(USE_SHARED_EEPROM, SPI_EEPROM) +#if ENABLED(SPI_EEPROM) -#include "../HAL.h" #include "eeprom_if.h" +void eeprom_init() {} + +#if ENABLED(USE_SHARED_EEPROM) + #define CMD_WREN 6 // WREN #define CMD_READ 2 // WRITE #define CMD_WRITE 2 // WRITE @@ -80,4 +83,5 @@ void eeprom_write_byte(uint8_t* pos, uint8_t value) { delay(EEPROM_WRITE_DELAY); // wait for page write to complete } -#endif // USE_SHARED_EEPROM && I2C_EEPROM +#endif // USE_SHARED_EEPROM +#endif // I2C_EEPROM From 2e21c725423e959904b9f09f7177648f849bf744 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 1 May 2020 00:52:37 -0500 Subject: [PATCH 0353/1454] Add ExtUI mesh items for Malyan LCD Fixes #17429 --- Marlin/src/lcd/extui_malyan_lcd.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 73de849087..2817b4143a 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -491,7 +491,16 @@ namespace ExtUI { void onLoadSettings(const char*) {} void onConfigurationStoreWritten(bool) {} void onConfigurationStoreRead(bool) {} - void onPidTuning(const result_t) {} + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) {} + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} + + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() {} + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) {} + #endif } #endif // MALYAN_LCD From dcd02284bea3ddfc3b9545bde2121a283d08d518 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 2 May 2020 00:03:28 +0000 Subject: [PATCH 0354/1454] [cron] Bump distribution date (2020-05-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a3cf749ccc..3ad1a424eb 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-01" + #define STRING_DISTRIBUTION_DATE "2020-05-02" #endif /** From 9b7807d40fbe7127874038dea920020f6c167cf9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 2 May 2020 15:39:23 -0500 Subject: [PATCH 0355/1454] Clean up M122 code --- Marlin/src/gcode/feature/trinamic/M122.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 0eb93a8006..b051877a7e 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -39,9 +39,10 @@ void GcodeSuite::M122() { #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) - const bool sflag = parser.seen('S'), s0 = sflag && !parser.value_bool(); - if (sflag) tmc_set_report_interval(s0 ? 0 : MONITOR_DRIVER_STATUS_INTERVAL_MS); - if (!s0 && parser.seenval('P')) tmc_set_report_interval(_MIN(parser.value_ushort(), MONITOR_DRIVER_STATUS_INTERVAL_MS)); + uint16_t interval = MONITOR_DRIVER_STATUS_INTERVAL_MS; + if (parser.seen('S') && !parser.value_bool()) interval = 0; + if (parser.seenval('P')) NOMORE(interval, parser.value_ushort()); + tmc_set_report_interval(interval); #endif if (parser.seen('V')) From 93946c2868a5c773497cfce1ea3657996bbae802 Mon Sep 17 00:00:00 2001 From: mojocorp Date: Sat, 2 May 2020 23:13:14 +0200 Subject: [PATCH 0356/1454] Fix ExtUI compile (#17834) --- Marlin/src/lcd/extui_example.cpp | 14 ++++++++------ Marlin/src/lcd/extui_malyan_lcd.cpp | 7 +++++-- 2 files changed, 13 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 900afdea04..3d99611d06 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -89,13 +89,15 @@ namespace ExtUI { // whether successful or not. } - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { - // Called when any mesh points are updated - } + #if HAS_MESH + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + // Called when any mesh points are updated + } - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { - // Called to indicate a special condition - } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #endif #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() { diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 2817b4143a..887738b3a6 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -491,8 +491,11 @@ namespace ExtUI { void onLoadSettings(const char*) {} void onConfigurationStoreWritten(bool) {} void onConfigurationStoreRead(bool) {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} + + #if HAS_MESH + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) {} + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} + #endif #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() {} From 288447d01ebfe73b4bc2a0d10bb925d6edaf8143 Mon Sep 17 00:00:00 2001 From: Mathias Gartner <36887952+MathiasGartner@users.noreply.github.com> Date: Sat, 2 May 2020 23:15:49 +0200 Subject: [PATCH 0357/1454] Fix XYZ types multiplication/division (#17826) --- Marlin/src/core/types.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 1212eb5ba2..6bcd4bd489 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -347,14 +347,14 @@ struct XYZval { FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } FI XYZval operator>>(const int &v) const { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } FI XYZval operator>>(const int &v) { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } FI XYZval operator<<(const int &v) const { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } From e4d8336175ee09b28d23220f446d07451ca3de43 Mon Sep 17 00:00:00 2001 From: Mathias Gartner <36887952+MathiasGartner@users.noreply.github.com> Date: Sat, 2 May 2020 23:15:49 +0200 Subject: [PATCH 0358/1454] Fix XYZ types multiplication/division (#17826) --- Marlin/src/core/types.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 1212eb5ba2..6bcd4bd489 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -347,14 +347,14 @@ struct XYZval { FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } FI XYZval operator>>(const int &v) const { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } FI XYZval operator>>(const int &v) { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } FI XYZval operator<<(const int &v) const { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } From 9381a76d757c348554611498b74f4aa6fd028504 Mon Sep 17 00:00:00 2001 From: Gurmeet Athwal Date: Sun, 3 May 2020 02:49:40 +0530 Subject: [PATCH 0359/1454] Add Cap:LONG_FILENAME (#17821) --- Marlin/src/gcode/host/M115.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index bd3a5b192b..824c2e166e 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -102,6 +102,9 @@ void GcodeSuite::M115() { // AUTOREPORT_SD_STATUS (M27 extension) cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); + // LONG_FILENAME_HOST_SUPPORT (M33) + cap_line(PSTR("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT)); + // THERMAL_PROTECTION cap_line(PSTR("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE)); From 52f3f3b5ab857fddf27ba97438cd165c816f6f46 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 2 May 2020 17:00:00 -0500 Subject: [PATCH 0360/1454] Fix motor current array --- Marlin/src/feature/digipot/digipot_mcp4451.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index c3c49f2c8c..87c6b679a0 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -82,7 +82,13 @@ void digipot_i2c_init() { Wire.begin(); #endif // Set up initial currents as defined in Configuration_adv.h - static const float digipot_motor_current[] PROGMEM = TERN(DIGIPOT_USE_RAW_VALUES, DIGIPOT_MOTOR_CURRENT, DIGIPOT_I2C_MOTOR_CURRENTS); + static const float digipot_motor_current[] PROGMEM = + #if ENABLED(DIGIPOT_USE_RAW_VALUES) + DIGIPOT_MOTOR_CURRENT + #else + DIGIPOT_I2C_MOTOR_CURRENTS + #endif + ; LOOP_L_N(i, COUNT(digipot_motor_current)) digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } From 208af8cb15ca35190845efdca171f83915a294fa Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 2 May 2020 15:24:51 -0700 Subject: [PATCH 0361/1454] Fix STM32 + SoftwareSerial compile (#17831) --- Marlin/src/HAL/STM32/HAL.cpp | 10 +--------- Marlin/src/HAL/STM32/timers.cpp | 14 +++++++++++--- Marlin/src/HAL/STM32/timers.h | 3 +++ buildroot/share/tests/BIGTREE_BTT002-tests | 4 +++- buildroot/share/tests/BIGTREE_SKR_PRO-tests | 4 +++- platformio.ini | 3 ++- 6 files changed, 23 insertions(+), 15 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index f146d7a87b..37cfb576d1 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -27,10 +27,6 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" -#if HAS_TMC_SW_SERIAL - #include "SoftwareSerial.h" -#endif - #if ENABLED(SRAM_EEPROM_EMULATION) #if STM32F7xx #include @@ -82,11 +78,7 @@ void HAL_init() { while (!LL_PWR_IsActiveFlag_BRR()); // Wait until backup regulator is initialized #endif - #if HAS_TMC_SW_SERIAL - SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0); - #endif - - TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0)); + SetSoftwareSerialTimerInterruptPriority(); } void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 3bbef2c609..0871fbc7d7 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -31,9 +31,6 @@ #define NUM_HARDWARE_TIMERS 2 -#ifndef SWSERIAL_TIMER_IRQ_PRIO - #define SWSERIAL_TIMER_IRQ_PRIO 1 -#endif #ifndef STEP_TIMER_IRQ_PRIO #define STEP_TIMER_IRQ_PRIO 2 #endif @@ -41,6 +38,13 @@ #define TEMP_TIMER_IRQ_PRIO 14 // 14 = after hardware ISRs #endif +#if HAS_TMC_SW_SERIAL + #include + #ifndef SWSERIAL_TIMER_IRQ_PRIO + #define SWSERIAL_TIMER_IRQ_PRIO 1 + #endif +#endif + #ifdef STM32F0xx #define HAL_TIMER_RATE (F_CPU) // Frequency of timer peripherals #define MCU_STEP_TIMER 16 @@ -175,4 +179,8 @@ TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) { return nullptr; } +void SetSoftwareSerialTimerInterruptPriority() { + TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0)); +} + #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6a04359c21..60d3b3aaf3 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -75,6 +75,9 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); +// Exposed here to allow all timer priority information to reside in timers.cpp +void SetSoftwareSerialTimerInterruptPriority(); + //TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally // FORCE_INLINE because these are used in performance-critical situations diff --git a/buildroot/share/tests/BIGTREE_BTT002-tests b/buildroot/share/tests/BIGTREE_BTT002-tests index 1ab40123b5..64e6322eca 100644 --- a/buildroot/share/tests/BIGTREE_BTT002-tests +++ b/buildroot/share/tests/BIGTREE_BTT002-tests @@ -12,7 +12,9 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 opt_set SERIAL_PORT 1 -exec_test $1 $2 "BigTreeTech BTT002 Default Configuration" +opt_set X_DRIVER_TYPE TMC2209 +opt_set Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" # clean up restore_configs diff --git a/buildroot/share/tests/BIGTREE_SKR_PRO-tests b/buildroot/share/tests/BIGTREE_SKR_PRO-tests index 238b54d4f8..7623bf3f66 100644 --- a/buildroot/share/tests/BIGTREE_SKR_PRO-tests +++ b/buildroot/share/tests/BIGTREE_SKR_PRO-tests @@ -23,7 +23,9 @@ opt_set TEMP_SENSOR_2 1 opt_set E0_AUTO_FAN_PIN PC10 opt_set E1_AUTO_FAN_PIN PC11 opt_set E2_AUTO_FAN_PIN PC12 -exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders with Auto-Fan" +opt_set X_DRIVER_TYPE TMC2209 +opt_set Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders with Auto-Fan and mixed TMC drivers" # clean up restore_configs diff --git a/platformio.ini b/platformio.ini index 9a6dbad1f1..dad4beb143 100644 --- a/platformio.ini +++ b/platformio.ini @@ -769,9 +769,10 @@ build_flags = ${common.build_flags} -DHAVE_HWSERIAL3 -DPIN_SERIAL2_RX=PD_6 -DPIN_SERIAL2_TX=PD_5 + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -lib_ignore = Adafruit NeoPixel, SailfishLCD, SlowSoftI2CMaster +lib_ignore = Adafruit NeoPixel, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial src_filter = ${common.default_src_filter} + # From db32af917157d6187b5fac4a39b18a2fe7f521b2 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Sat, 2 May 2020 16:30:51 -0600 Subject: [PATCH 0362/1454] Fix ExtUI + Archim compile, typos (#17825) --- .../lcd/extui/lib/ftdi_eve_touch_ui/config.h | 100 +----------------- .../ftdi_eve_lib/basic/spi.cpp | 2 +- .../ftdi_eve_lib/basic/spi.h | 2 +- .../screens/advanced_settings_menu.cpp | 7 +- .../ftdi_eve_touch_ui/screens/tune_menu.cpp | 6 +- Marlin/src/lcd/extui_dgus_lcd.cpp | 14 +-- 6 files changed, 17 insertions(+), 114 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h index 458c901206..dadb0328ca 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h @@ -23,102 +23,4 @@ #include "compat.h" -// Define the display board used (see "ftdi_eve_boards.h" for definitions) - -//#define LCD_FTDI_VM800B35A // FTDI 3.5" 320x240 with FT800 -//#define LCD_4DSYSTEMS_4DLCD_FT843 // 4D Systems 4.3" 480x272 -//#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" 480x272 -//#define LCD_HAOYU_FT810CB // Haoyu with 5" 800x480 -//#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD User Interface - -// Leave the following commented out to use a board's default resolution. -// If you have changed the LCD panel, you may override the resolution -// below (see "ftdi_eve_resolutions.h" for definitions): - -//#define TOUCH_UI_320x240 -//#define TOUCH_UI_480x272 -//#define TOUCH_UI_800x480 - -// Define the printer interface or pins used (see "ui_pin_mappings.h" for definitions): - -//#define CR10_TFT_PINMAP -//#define AO_EXP1_DEPRECATED_PINMAP // UltraLCD EXP1 connector, old AlephObject's wiring -//#define AO_EXP1_PINMAP // UltraLCD EXP1 connector, new AlephObject's wiring -//#define AO_EXP2_PINMAP // UltraLCD EXP2 connector, new AlephObject's wiring -//#define OTHER_PIN_LAYOUT - -// Otherwise. Define all the pins manually: - -#ifdef OTHER_PIN_LAYOUT - // Select interfacing pins, the following pin specifiers are supported: - // - // ARDUINO_DIGITAL_1 - Arduino pin via digitalWrite/digitalRead - // AVR_A1 - Fast AVR port access via PORTA/PINA/DDRA - // 1 - When compiling Marlin, use Marlin pin IDs. - - // The pins for CS and MOD_RESET (PD) must be chosen. - #define CLCD_MOD_RESET 9 - #define CLCD_SPI_CS 10 - - // If using software SPI, specify pins for SCLK, MOSI, MISO - //#define CLCD_USE_SOFT_SPI - #ifdef CLCD_USE_SOFT_SPI - #define CLCD_SOFT_SPI_MOSI 11 - #define CLCD_SOFT_SPI_MISO 12 - #define CLCD_SOFT_SPI_SCLK 13 - #endif -#endif - -// Defines how to orient the display. An inverted (i.e. upside-down) display -// is supported on the FT800. The FT810 or better also support a portrait -// and mirrored orientation. -//#define TOUCH_UI_INVERTED -//#define TOUCH_UI_PORTRAIT -//#define TOUCH_UI_MIRRORED - -// Enable UTF8 processing and rendering. Unsupported characters -// will be shown as '?'. -//#define TOUCH_UI_USE_UTF8 -#ifdef TOUCH_UI_USE_UTF8 - // Western accents support. These accented characters use - // combined bitmaps and require relatively little storage. - #define TOUCH_UI_UTF8_WESTERN_CHARSET - #ifdef TOUCH_UI_UTF8_WESTERN_CHARSET - // Additional character groups. These characters require - // full bitmaps and take up considerable storage: - //#define TOUCH_UI_UTF8_SUPERSCRIPTS // ¹ ² ³ - //#define TOUCH_UI_UTF8_COPYRIGHT // © ® - //#define TOUCH_UI_UTF8_GERMANIC // ß - //#define TOUCH_UI_UTF8_SCANDINAVIAN // Æ Ð Ø Þ æ ð ø þ - //#define TOUCH_UI_UTF8_PUNCTUATION // « » ¿ ¡ - //#define TOUCH_UI_UTF8_CURRENCY // ¢ £ ¤ ¥ - //#define TOUCH_UI_UTF8_ORDINALS // º ª - //#define TOUCH_UI_UTF8_MATHEMATICS // ± × ÷ - //#define TOUCH_UI_UTF8_FRACTIONS // ¼ ½ ¾ - //#define TOUCH_UI_UTF8_SYMBOLS // µ ¶ ¦ § ¬ - #endif -#endif - -// When labels do not fit buttons, use smaller font -//#define TOUCH_UI_FIT_TEXT - -// Enable support for selection of languages at run-time -// (otherwise will use the value of LCD_LANGUAGE) -//#define TOUCH_UI_LANGUAGE_MENU - -// Use a numeric passcode for "Parental lock". -// This is a recommended for smaller displays. -//#define TOUCH_UI_PASSCODE - -// The timeout (in ms) to return to the status screen from sub-menus -//#define LCD_TIMEOUT_TO_STATUS 15000 - -// Enable this to debug the event framework -//#define TOUCH_UI_DEBUG - -// Enable the developer's menu and screens -//#define DEVELOPER_SCREENS - -// Sets the SPI speed in Hz - -#define SPI_FREQUENCY 8000000 >> SPI_SPEED +// Configure this display with options in Configuration_adv.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 9506eefc44..583b03911d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -29,7 +29,7 @@ namespace FTDI { #ifndef CLCD_USE_SOFT_SPI - #ifndef __AVR__ + #ifdef CLCD_SPI_BUS SPIClass EVE_SPI(CLCD_SPI_BUS); #endif SPISettings SPI::spi_settings(SPI_FREQUENCY, MSBFIRST, SPI_MODE0); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h index 9f6c123179..3e10b4b962 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h @@ -28,7 +28,7 @@ namespace FTDI { - #if defined(__AVR__) || defined(CLCD_USE_SOFT_SPI) + #if !defined(CLCD_SPI_BUS) || defined(CLCD_USE_SOFT_SPI) #define SPI_OBJ ::SPI #else extern SPIClass EVE_SPI; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index bf01ffac27..d015f46ffe 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -99,9 +99,8 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .enabled(ENABLED(SENSORLESS_HOMING)) .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled(EITHER(HAS_MULTI_HOTEND, BLTOUCH)) - .tag(4) .button( OFFSETS_POS, GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_OFFSETS_MENU, MSG_RESET_BLTOUCH)) - .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - ) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_OFFSETS_MENU, MSG_RESET_BLTOUCH))) + .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) .tag(15).button( DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) @@ -109,7 +108,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) - .tag(7) .button( JERK_POS, GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK)) + .tag(7) .button( JERK_POS, GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK))) .enabled(ENABLED(BACKLASH_GCODE)) .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) .colors(action_btn) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp index e85dc6f0fd..ae0462683d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp @@ -72,14 +72,14 @@ void TuneMenu::onRedraw(draw_mode_t what) { .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(9).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .enabled(EITHER(HAS_BED_PROBE, BABYSTEPPING)) - .tag(4).button( NUDGE_NOZ_POS, GET_TEXT_F(TERN(BABYSTEPPING, MSG_NUDGE_NOZZLE, MSG_ZPROBE_ZOFFSET)) + .tag(4).button( NUDGE_NOZ_POS, GET_TEXT_F(TERN(BABYSTEPPING, MSG_NUDGE_NOZZLE, MSG_ZPROBE_ZOFFSET))) .tag(5).button( SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) .tag(isPrintingFromMediaPaused() ? 7 : 6) .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) .button( PAUSE_POS, isPrintingFromMediaPaused() ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) - .tag(8).button( STOP_POS, GET_TEXT_F(MSG_STOP_PRINT)) - .tag(1).colors(action_btn) + .tag(8).button( STOP_POS, GET_TEXT_F(MSG_STOP_PRINT)) + .tag(1).colors(action_btn) .button( BACK_POS, GET_TEXT_F(MSG_BACK)); } #undef GRID_COLS diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 74e16fbdbc..c29bc5a114 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -106,13 +106,15 @@ namespace ExtUI { // whether successful or not. } - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { - // Called when any mesh points are updated - } + #if HAS_MESH + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + // Called when any mesh points are updated + } - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { - // Called to indicate a special condition - } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #endif #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() { From 8d425c672002bd90fad5f2778bd544ef69fb9e8d Mon Sep 17 00:00:00 2001 From: Eric Ptak Date: Sun, 3 May 2020 01:27:18 +0200 Subject: [PATCH 0363/1454] Fix missing ProbeTempComp refs (#17833) --- Marlin/src/feature/probe_temp_comp.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index b773536a5d..92ff2e9771 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -50,6 +50,10 @@ const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = { #endif }; +constexpr xyz_pos_t ProbeTempComp::park_point; +constexpr xy_pos_t ProbeTempComp::measure_point; +constexpr int ProbeTempComp::probe_calib_bed_temp; + uint8_t ProbeTempComp::calib_idx; // = 0 float ProbeTempComp::init_measurement; // = 0.0 From 739b738e7f4f57e7d4ad487cf5e4ddd10db48e44 Mon Sep 17 00:00:00 2001 From: "Dipl.-Ing. Raoul Rubien, BSc" Date: Sun, 3 May 2020 01:30:23 +0200 Subject: [PATCH 0364/1454] Permit more Creality pin overrides (#17820) --- Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index 5134812c1b..dd4cb4ea08 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -43,7 +43,10 @@ #define SD_DETECT_PIN 49 // Always define onboard SD detect #endif -#define PS_ON_PIN 40 // Used by CR2020 Industrial series +#ifndef PS_ON_PIN + #define PS_ON_PIN 40 // Used by CR2020 Industrial series +#endif + #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) #define CASE_LIGHT_PIN 65 @@ -61,4 +64,6 @@ #define EXP4_PIN 12 // PS_ON_PIN #define SUICIDE_PIN 12 // Used by CR2020 Industrial series -#define SUICIDE_PIN_INVERTING true // Used by CR2020 Industrial series +#ifndef SUICIDE_PIN_INVERTING + #define SUICIDE_PIN_INVERTING true +#endif From cba4c5a756997404a3ea7520747503754022af80 Mon Sep 17 00:00:00 2001 From: "Dipl.-Ing. Raoul Rubien, BSc" Date: Sun, 3 May 2020 01:32:01 +0200 Subject: [PATCH 0365/1454] Fix missing var for DGUS_LCD_UI_ORIGIN (#17819) --- Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h index 756b91ddbd..85788df300 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h @@ -192,7 +192,7 @@ constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer //constexpr uint16_t VP_Flowrate_E5 = 0x309A; constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) -//constexpr uint16_t VP_Fan1_Percentage = 0x33A2; // 2 Byte Integer (0..100) +constexpr uint16_t VP_Fan1_Percentage = 0x33A2; // 2 Byte Integer (0..100) //constexpr uint16_t VP_Fan2_Percentage = 0x33A4; // 2 Byte Integer (0..100) //constexpr uint16_t VP_Fan3_Percentage = 0x33A6; // 2 Byte Integer (0..100) From 7613383e7b5d3c71ad18e4ee9823d353403d01c2 Mon Sep 17 00:00:00 2001 From: Axel Date: Sat, 2 May 2020 19:45:54 -0400 Subject: [PATCH 0366/1454] Add Rostock 301 thermistors (22, 23) (#17806) --- Marlin/Configuration.h | 2 + Marlin/src/module/thermistor/thermistor_22.h | 72 +++++++++++ Marlin/src/module/thermistor/thermistor_23.h | 128 +++++++++++++++++++ Marlin/src/module/thermistor/thermistors.h | 6 + 4 files changed, 208 insertions(+) create mode 100644 Marlin/src/module/thermistor/thermistor_22.h create mode 100644 Marlin/src/module/thermistor/thermistor_23.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 9564cad8a4..de61230a6f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -387,6 +387,8 @@ * 18 : ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 * 20 : Pt100 with circuit in the Ultimainboard V2.x with 5v excitation (AVR) * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....) + * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB) + * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB) * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x * 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 * 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup diff --git a/Marlin/src/module/thermistor/thermistor_22.h b/Marlin/src/module/thermistor/thermistor_22.h new file mode 100644 index 0000000000..b3ef68a47e --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_22.h @@ -0,0 +1,72 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +// 100k hotend thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB +const short temptable_22[][2] PROGMEM = { + { OV( 1), 352 }, + { OV( 6), 341 }, + { OV( 11), 330 }, + { OV( 16), 319 }, + { OV( 20), 307 }, + { OV( 26), 296 }, + { OV( 31), 285 }, + { OV( 40), 274 }, + { OV( 51), 263 }, + { OV( 61), 251 }, + { OV( 72), 245 }, + { OV( 77), 240 }, + { OV( 82), 237 }, + { OV( 87), 232 }, + { OV( 91), 229 }, + { OV( 94), 227 }, + { OV( 97), 225 }, + { OV( 100), 223 }, + { OV( 104), 221 }, + { OV( 108), 219 }, + { OV( 115), 214 }, + { OV( 126), 209 }, + { OV( 137), 204 }, + { OV( 147), 200 }, + { OV( 158), 193 }, + { OV( 167), 192 }, + { OV( 177), 189 }, + { OV( 197), 163 }, + { OV( 230), 174 }, + { OV( 267), 165 }, + { OV( 310), 158 }, + { OV( 336), 151 }, + { OV( 379), 143 }, + { OV( 413), 138 }, + { OV( 480), 127 }, + { OV( 580), 110 }, + { OV( 646), 100 }, + { OV( 731), 88 }, + { OV( 768), 84 }, + { OV( 861), 69 }, + { OV( 935), 50 }, + { OV( 975), 38 }, + { OV(1001), 27 }, + { OV(1011), 22 }, + { OV(1015), 13 }, + { OV(1020), 6 }, + { OV(1023), 0 } +}; diff --git a/Marlin/src/module/thermistor/thermistor_23.h b/Marlin/src/module/thermistor/thermistor_23.h new file mode 100644 index 0000000000..46c025d21a --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_23.h @@ -0,0 +1,128 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +// 100k hotbed thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB +const short temptable_23[][2] PROGMEM = { + { OV( 1), 938 }, + { OV( 11), 423 }, + { OV( 21), 351 }, + { OV( 31), 314 }, + { OV( 41), 290 }, + { OV( 51), 272 }, + { OV( 61), 258 }, + { OV( 71), 247 }, + { OV( 81), 237 }, + { OV( 91), 229 }, + { OV( 101), 221 }, + { OV( 111), 215 }, + { OV( 121), 209 }, + { OV( 131), 204 }, + { OV( 141), 199 }, + { OV( 151), 195 }, + { OV( 161), 190 }, + { OV( 171), 187 }, + { OV( 181), 183 }, + { OV( 191), 179 }, + { OV( 201), 176 }, + { OV( 211), 173 }, + { OV( 221), 170 }, + { OV( 231), 167 }, + { OV( 241), 165 }, + { OV( 251), 162 }, + { OV( 261), 160 }, + { OV( 271), 157 }, + { OV( 281), 155 }, + { OV( 291), 153 }, + { OV( 301), 150 }, + { OV( 311), 148 }, + { OV( 321), 146 }, + { OV( 331), 144 }, + { OV( 341), 142 }, + { OV( 351), 140 }, + { OV( 361), 139 }, + { OV( 371), 137 }, + { OV( 381), 135 }, + { OV( 391), 133 }, + { OV( 401), 131 }, + { OV( 411), 130 }, + { OV( 421), 128 }, + { OV( 431), 126 }, + { OV( 441), 125 }, + { OV( 451), 123 }, + { OV( 461), 122 }, + { OV( 471), 120 }, + { OV( 481), 119 }, + { OV( 491), 117 }, + { OV( 501), 116 }, + { OV( 511), 114 }, + { OV( 521), 113 }, + { OV( 531), 111 }, + { OV( 541), 110 }, + { OV( 551), 108 }, + { OV( 561), 107 }, + { OV( 571), 105 }, + { OV( 581), 104 }, + { OV( 591), 102 }, + { OV( 601), 101 }, + { OV( 611), 100 }, + { OV( 621), 98 }, + { OV( 631), 97 }, + { OV( 641), 95 }, + { OV( 651), 94 }, + { OV( 661), 92 }, + { OV( 671), 91 }, + { OV( 681), 90 }, + { OV( 691), 88 }, + { OV( 701), 87 }, + { OV( 711), 85 }, + { OV( 721), 84 }, + { OV( 731), 82 }, + { OV( 741), 81 }, + { OV( 751), 79 }, + { OV( 761), 77 }, + { OV( 771), 76 }, + { OV( 781), 74 }, + { OV( 791), 72 }, + { OV( 801), 71 }, + { OV( 811), 69 }, + { OV( 821), 67 }, + { OV( 831), 65 }, + { OV( 841), 63 }, + { OV( 851), 62 }, + { OV( 861), 60 }, + { OV( 871), 57 }, + { OV( 881), 55 }, + { OV( 891), 53 }, + { OV( 901), 51 }, + { OV( 911), 48 }, + { OV( 921), 45 }, + { OV( 931), 42 }, + { OV( 941), 39 }, + { OV( 951), 36 }, + { OV( 961), 32 }, + { OV( 971), 28 }, + { OV( 981), 25 }, + { OV( 991), 23 }, + { OV(1001), 21 }, + { OV(1011), 19 }, + { OV(1021), 5 } +}; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 032386c2bd..b66e30b5cc 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -109,6 +109,12 @@ #if ANY_THERMISTOR_IS(21) // Pt100 with INA826 amp with 3.3v excitation based on "Pt100 with INA826 amp on Ultimaker v2.0 electronics" #include "thermistor_21.h" #endif +#if ANY_THERMISTOR_IS(22) // Thermistor in a Rostock 301 hot end, calibrated with a multimeter + #include "thermistor_22.h" +#endif +#if ANY_THERMISTOR_IS(23) // By AluOne #12622. Formerly 22 above. May need calibration/checking. + #include "thermistor_23.h" +#endif #if ANY_THERMISTOR_IS(51) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 1 kOhm, "EPCOS" #include "thermistor_51.h" #endif From ef02358378647666cdb00ef1fef73752c78399c8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 3 May 2020 00:06:47 +0000 Subject: [PATCH 0367/1454] [cron] Bump distribution date (2020-05-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3ad1a424eb..35b25540d9 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-02" + #define STRING_DISTRIBUTION_DATE "2020-05-03" #endif /** From 6b3ed0f320074a266d1705fbd0120fc444292fa1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 2 May 2020 21:31:34 -0500 Subject: [PATCH 0368/1454] Cleanup in language.h --- Marlin/src/core/language.h | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 40a0d7b8cb..d7b50a52ce 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -220,12 +220,10 @@ #define STR_KILL_BUTTON "!! KILL caused by KILL button/pin" // temperature.cpp strings -#define STR_PID_AUTOTUNE_PREFIX "PID Autotune" -#define STR_PID_AUTOTUNE_START STR_PID_AUTOTUNE_PREFIX " start" -#define STR_PID_AUTOTUNE_FAILED STR_PID_AUTOTUNE_PREFIX " failed!" -#define STR_PID_BAD_EXTRUDER_NUM STR_PID_AUTOTUNE_FAILED " Bad extruder number" -#define STR_PID_TEMP_TOO_HIGH STR_PID_AUTOTUNE_FAILED " Temperature too high" -#define STR_PID_TIMEOUT STR_PID_AUTOTUNE_FAILED " timeout" +#define STR_PID_AUTOTUNE_START "PID Autotune start" +#define STR_PID_BAD_EXTRUDER_NUM "PID Autotune failed! Bad extruder number" +#define STR_PID_TEMP_TOO_HIGH "PID Autotune failed! Temperature too high" +#define STR_PID_TIMEOUT "PID Autotune failed! timeout" #define STR_BIAS " bias: " #define STR_D_COLON " d: " #define STR_T_MIN " min: " @@ -236,7 +234,7 @@ #define STR_KP " Kp: " #define STR_KI " Ki: " #define STR_KD " Kd: " -#define STR_PID_AUTOTUNE_FINISHED STR_PID_AUTOTUNE_PREFIX " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h" +#define STR_PID_AUTOTUNE_FINISHED "PID Autotune finished! Put the last Kp, Ki and Kd constants from below into Configuration.h" #define STR_PID_DEBUG " PID_DEBUG " #define STR_PID_DEBUG_INPUT ": Input " #define STR_PID_DEBUG_OUTPUT " Output " From 3ea1c8a6faf941a7e11e9b938be8d050fbf6c1e5 Mon Sep 17 00:00:00 2001 From: animavitis Date: Sun, 3 May 2020 05:12:52 +0200 Subject: [PATCH 0369/1454] Support for Ortur 4.3 mainboard (#17790) --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 + Marlin/src/pins/ramps/pins_ORTUR_4.h | 116 +++++++++++++++++++++++++++ 3 files changed, 119 insertions(+) create mode 100644 Marlin/src/pins/ramps/pins_ORTUR_4.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index bbbd404b32..82a969b71a 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -104,6 +104,7 @@ #define BOARD_TANGO 1148 // BIQU Tango V1 #define BOARD_MKS_GEN_L_V2 1149 // MKS GEN L V2 #define BOARD_COPYMASTER_3D 1150 // Copymaster 3D +#define BOARD_ORTUR_4 1151 // Ortur 4 // // RAMBo and derivatives diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index d4ba832269..dc42d80706 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -190,6 +190,8 @@ #include "ramps/pins_MKS_GEN_L_V2.h" // ATmega2560 env:mega2560 #elif MB(COPYMASTER_3D) #include "ramps/pins_COPYMASTER_3D.h" // ATmega2560 env:mega2560 +#elif MB(ORTUR_4) + #include "ramps/pins_ORTUR_4.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives diff --git a/Marlin/src/pins/ramps/pins_ORTUR_4.h b/Marlin/src/pins/ramps/pins_ORTUR_4.h new file mode 100644 index 0000000000..91236cc38f --- /dev/null +++ b/Marlin/src/pins/ramps/pins_ORTUR_4.h @@ -0,0 +1,116 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Ortur 4 Arduino Mega based on RAMPS v1.4 pin assignments + */ + +#define BOARD_INFO_NAME "Ortur 4.3" +#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME + +// +// Servos +// +#define SERVO0_PIN 29 + +// +// Limit Switches +// +#define X_MAX_PIN 18 +#define Z_MIN_PIN 63 + +#define Z_MIN_PROBE_PIN 2 +#define FIL_RUNOUT_PIN 59 + +// +// Steppers +// +#define E0_CS_PIN 44 +#define E1_CS_PIN 42 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 15 // Analog Input +#define TEMP_1_PIN 13 // Analog Input + +// +// Software serial +// +#define X_SERIAL_TX_PIN 59 +#define X_SERIAL_RX_PIN 63 + +#define Y_SERIAL_TX_PIN 64 +#define Y_SERIAL_RX_PIN 40 + +#define Z_SERIAL_TX_PIN 44 +#define Z_SERIAL_RX_PIN 42 + +#define E0_SERIAL_TX_PIN 66 +#define E0_SERIAL_RX_PIN 65 + +#include "pins_RAMPS.h" + +// +// Steppers +// +#undef E0_STEP_PIN +#undef E0_DIR_PIN +#undef E0_ENABLE_PIN +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 + +#undef E1_STEP_PIN +#undef E1_DIR_PIN +#undef E1_ENABLE_PIN +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 24 + +// +// LCD / Controller +// +#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #undef BEEPER_PIN + #define BEEPER_PIN 35 + + #undef LCD_PINS_RS + #undef LCD_PINS_ENABLE + #undef LCD_PINS_D4 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 23 + #define LCD_PINS_D4 37 + + #undef LCD_SDSS + #undef SD_DETECT_PIN + #define LCD_SDSS 53 + #define SD_DETECT_PIN 49 + + #undef BTN_EN1 + #undef BTN_EN2 + #undef BTN_ENC + #define BTN_EN1 29 + #define BTN_EN2 25 + #define BTN_ENC 16 +#endif From 120fcd1215d9f831665a3e3681e64450adace9d3 Mon Sep 17 00:00:00 2001 From: Stephan Date: Sun, 3 May 2020 05:19:05 +0200 Subject: [PATCH 0370/1454] Support GT2560 3rd extruder (#17797) --- Marlin/src/pins/mega/pins_GT2560_V3.h | 6 +++--- Marlin/src/pins/mega/pins_GT2560_V3_A20.h | 2 ++ 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 08f9018a29..34d1f81227 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -121,7 +121,7 @@ // #define TEMP_0_PIN 11 // Analog Input #define TEMP_1_PIN 9 // Analog Input -#define TEMP_2_PIN 1 // Analog Input +#define TEMP_2_PIN 8 // Analog Input #define TEMP_BED_PIN 10 // Analog Input // @@ -129,7 +129,7 @@ // #define HEATER_0_PIN 10 #define HEATER_1_PIN 3 -#define HEATER_2_PIN 1 +#define HEATER_2_PIN 2 #define HEATER_BED_PIN 4 #define FAN_PIN 9 #define FAN1_PIN 8 @@ -140,7 +140,7 @@ // #define SD_DETECT_PIN 38 #define SDSS 53 -#define LED_PIN 6 +#define LED_PIN 13 // Use 6 (case light) for external LED. 13 is internal (yellow) LED. #define PS_ON_PIN 12 #define SUICIDE_PIN 54 // This pin must be enabled at boot to keep power flowing diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h index 06ac9fd9df..5e322a0356 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h @@ -30,6 +30,8 @@ #define LCD_PINS_D4 21 #define LCD_PINS_D7 6 +#define SPEAKER // The speaker can produce tones + #if ENABLED(NEWPANEL) #define BTN_EN1 16 #define BTN_EN2 17 From 9a4a768ee393c269e95e93005991a02c82e11787 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Sun, 3 May 2020 05:21:40 +0200 Subject: [PATCH 0371/1454] Fix frequency limit editing (#17763) --- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 9828e7ec80..0f91e1de1d 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -415,7 +415,7 @@ void menu_cancelobject(); #ifdef XY_FREQUENCY_LIMIT EDIT_ITEM(int8, MSG_XY_FREQUENCY_LIMIT, &planner.xy_freq_limit_hz, 0, 100, planner.refresh_frequency_limit, true); - editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255 * 100)); // percent to u8 + editable.uint8 = uint8_t(LROUND(planner.xy_freq_min_speed_factor * 255)); // percent to u8 EDIT_ITEM(percent, MSG_XY_FREQUENCY_FEEDRATE, &editable.uint8, 3, 255, []{ planner.set_min_speed_factor_u8(editable.uint8); }, true); #endif From 0c68794fa920838c289373314c9e1b172bbfa676 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C5=A0t=C4=9Bp=C3=A1n=20Daleck=C3=BD?= <36531759+daleckystepan@users.noreply.github.com> Date: Sun, 3 May 2020 06:59:09 +0200 Subject: [PATCH 0372/1454] Improve JD acosx implementation (#17817) --- Marlin/src/module/planner.cpp | 100 +++++++++++++++++++++++++++------- Marlin/src/module/planner.h | 15 ++++- 2 files changed, 93 insertions(+), 22 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 117a8b6fda..54714715f2 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2304,28 +2304,87 @@ bool Planner::_populate_block(block_t * const block, bool split_move, const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec), sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive. - vmax_junction_sqr = (junction_acceleration * junction_deviation_mm * sin_theta_d2) / (1.0f - sin_theta_d2); + vmax_junction_sqr = JUNC_SQ(junction_acceleration, sin_theta_d2); if (block->millimeters < 1) { - // Fast acos approximation (max. error +-0.033 rads) - // Based on MinMax polynomial published by W. Randolph Franklin, see - // https://wrf.ecse.rpi.edu/Research/Short_Notes/arcsin/onlyelem.html - // (acos(x) = pi / 2 - asin(x)) - const float neg = junction_cos_theta < 0 ? -1 : 1, - t = neg * junction_cos_theta, - asinx = 0.032843707f - + t * (-1.451838349f - + t * ( 29.66153956f - + t * (-131.1123477f - + t * ( 262.8130562f - + t * (-242.7199627f + t * 84.31466202f) )))), - junction_theta = RADIANS(90) - neg * asinx; + t = neg * junction_cos_theta; // If angle is greater than 135 degrees (octagon), find speed for approximate arc - if (junction_theta > RADIANS(135)) { - // NOTE: MinMax acos approximation and thereby also junction_theta top out at pi-0.033, which avoids division by 0 - const float limit_sqr = block->millimeters / (RADIANS(180) - junction_theta) * junction_acceleration; + if (t < -0.7071067812f) { + + #if ENABLED(JD_USE_MATH_ACOS) + + #error "TODO: Inline maths with the MCU / FPU." + + #elif ENABLED(JD_USE_LOOKUP_TABLE) + + // Fast acos approximation (max. error +-0.01 rads) + // Based on LUT table and linear interpolation + + /** + * // Generate the JD Lookup Table + * constexpr float c = 1.00751317f; // Correction factor to center error around 0 + * for (int i = 0; i < jd_lut_count - 1; ++i) { + * const float x0 = (sq(i) - 1) / sq(i), + * y0 = acos(x0) * (i ? c : 1), + * x1 = 0.5 * x0 + 0.5, + * y1 = acos(x1) * c; + * jd_lut_k[i] = (y0 - y1) / (x0 - x1); + * jd_lut_b[i] = (y1 * x0 - y0 * x1) / (x0 - x1); + * } + * jd_lut_k[jd_lut_count - 1] = jd_lut_b[jd_lut_count - 1] = 0; + * + * // Compute correction factor (Set c to 1.0f first!) + * float min = INFINITY, max = -min; + * for (float t = 0; t <= 1; t += 0.0003f) { + * const float e = acos(t) / approx(t); + * if (isfinite(e)) { + * NOMORE(min, e); + * NOLESS(max, e); + * } + * } + * fprintf(stderr, "%.9gf, ", (min + max) / 2); + */ + static constexpr int16_t jd_lut_count = 15; + static constexpr uint16_t jd_lut_tll = 1 << jd_lut_count; + static constexpr int16_t jd_lut_tll0 = __builtin_clz(jd_lut_tll) + 1; // i.e., 16 - jd_lut_count + static constexpr float jd_lut_k[jd_lut_count] PROGMEM = { + -1.03146219f, -1.30760407f, -1.75205469f, -2.41705418f, -3.37768555f, + -4.74888229f, -6.69648552f, -9.45659828f, -13.3640289f, -18.8927879f, + -26.7136307f, -37.7754059f, -53.4200745f, -75.5457306f, 0.0f }; + static constexpr float jd_lut_b[jd_lut_count] PROGMEM = { + 1.57079637f, 1.70886743f, 2.04220533f, 2.62408018f, 3.52467203f, + 4.85301876f, 6.77019119f, 9.50873947f, 13.4009094f, 18.9188652f, + 26.7320709f, 37.7884521f, 53.4292908f, 75.5522461f, 0.0f }; + + const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(int16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; + + float junction_theta = t * pgm_read_float(&jd_lut_k[idx]) + pgm_read_float(&jd_lut_b[idx]); + if (neg > 0) junction_theta = RADIANS(180) - junction_theta; + + #else + + // Fast acos(-t) approximation (max. error +-0.033rad = 1.89°) + // Based on MinMax polynomial published by W. Randolph Franklin, see + // https://wrf.ecse.rpi.edu/Research/Short_Notes/arcsin/onlyelem.html + // acos( t) = pi / 2 - asin(x) + // acos(-t) = pi - acos(t) ... pi / 2 + asin(x) + + const float asinx = 0.032843707f + + t * (-1.451838349f + + t * ( 29.66153956f + + t * (-131.1123477f + + t * ( 262.8130562f + + t * (-242.7199627f + + t * ( 84.31466202f ) ))))), + junction_theta = RADIANS(90) + neg * asinx; // acos(-t) + + // NOTE: junction_theta bottoms out at 0.033 which avoids divide by 0. + + #endif + + const float limit_sqr = (block->millimeters * junction_acceleration) / junction_theta; NOMORE(vmax_junction_sqr, limit_sqr); } } @@ -2363,11 +2422,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Start with a safe speed (from which the machine may halt to stop immediately). float safe_speed = nominal_speed; - #ifdef TRAVEL_EXTRA_XYJERK - const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; - #else - constexpr float extra_xyjerk = 0; + #ifndef TRAVEL_EXTRA_XYJERK + #define TRAVEL_EXTRA_XYJERK 0 #endif + const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; uint8_t limited = 0; TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(i) { diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 7b029cba01..ccc7faf706 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -32,6 +32,17 @@ #include "../MarlinCore.h" +#if HAS_JUNCTION_DEVIATION + // Enable this option for perfect accuracy but maximum + // computation. Should be fine on ARM processors. + //#define JD_USE_MATH_ACOS + + // Disable this option to save 120 bytes of PROGMEM, + // but incur increased computation and a reduction + // in accuracy. + #define JD_USE_LOOKUP_TABLE +#endif + #include "motion.h" #include "../gcode/queue.h" @@ -827,9 +838,11 @@ class Planner { static void autotemp_update(); #endif + #define JUNC_SQ(N,ST) (junction_deviation_mm * (N) * (ST) / (1.0f - (ST))) + #if HAS_LINEAR_E_JERK FORCE_INLINE static void recalculate_max_e_jerk() { - #define GET_MAX_E_JERK(N) SQRT(SQRT(0.5) * junction_deviation_mm * (N) * RECIPROCAL(1.0 - SQRT(0.5))) + #define GET_MAX_E_JERK(N) SQRT(JUNC_SQ(N,SQRT(0.5))) #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(i, EXTRUDERS) max_e_jerk[i] = GET_MAX_E_JERK(settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]); From 36efe75ad13a8df9f642cde1fe067358d9fa8d25 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Sun, 3 May 2020 07:32:25 +0200 Subject: [PATCH 0373/1454] Followup for Tool Migration (#17800) --- Marlin/src/module/temperature.cpp | 5 +++++ Marlin/src/module/tool_change.cpp | 28 ++++++++++++++++++++++------ 2 files changed, 27 insertions(+), 6 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 78f8a19cf6..a456aa8af3 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2959,6 +2959,11 @@ void Temperature::tick() { , const bool click_to_cancel/*=false*/ #endif ) { + + #if ENABLED(AUTOTEMP) + REMEMBER(1, planner.autotemp_enabled, false); + #endif + #if TEMP_RESIDENCY_TIME > 0 millis_t residency_start_ms = 0; bool first_loop = true; diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index c0f7909a3c..36830f2c6e 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -790,6 +790,11 @@ void tool_change_prime() { const bool ok = TERN1(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); + #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 + // Store and stop fan. Restored on any exit. + REMEMBER(fan, thermalManager.fan_speed[TOOLCHANGE_FS_FAN], 0); + #endif + // Z raise if (ok) { // Do a small lift to avoid the workpiece in the move back (below) @@ -820,11 +825,10 @@ void tool_change_prime() { #endif // Cool down with fan - #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN - const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; + #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; gcode.dwell(toolchange_settings.fan_time * 1000); - thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = fansp; + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = 0; #endif // Move back @@ -933,6 +937,11 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool != old_tool) { destination = current_position; + #if BOTH(TOOLCHANGE_FILAMENT_SWAP, HAS_FAN) && TOOLCHANGE_FS_FAN >= 0 + // Store and stop fan. Restored on any exit. + REMEMBER(fan, thermalManager.fan_speed[TOOLCHANGE_FS_FAN], 0); + #endif + // Z raise before retraction #if ENABLED(TOOLCHANGE_ZRAISE_BEFORE_RETRACT) && DISABLED(SWITCHING_NOZZLE) if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { @@ -1104,11 +1113,10 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // Cool down with fan - #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN - const int16_t fansp = thermalManager.fan_speed[TOOLCHANGE_FS_FAN]; + #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = toolchange_settings.fan_speed; gcode.dwell(toolchange_settings.fan_time * 1000); - thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = fansp; + thermalManager.fan_speed[TOOLCHANGE_FS_FAN] = 0; #endif } #endif @@ -1157,6 +1165,11 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { unscaled_e_move(toolchange_settings.extra_resume + TOOLCHANGE_FS_WIPE_RETRACT, MMM_TO_MMS(toolchange_settings.unretract_speed)); current_position.e = 0; sync_plan_position_e(); // New extruder primed and set to 0 + + // Restart Fan + #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 + RESTORE(fan); + #endif } #endif @@ -1257,6 +1270,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { thermalManager.wait_for_hotend(active_extruder); #endif + // Migrate Linear Advance K factor to the new extruder + TERN_(LIN_ADVANCE, planner.extruder_advance_K[active_extruder] = planner.extruder_advance_K[migration_extruder]); + // Perform the tool change tool_change(migration_extruder); From 9a6934874a920afb91f0473add66f102c18f4798 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 3 May 2020 01:24:39 -0500 Subject: [PATCH 0374/1454] Add XYZ_NO_FRAME option --- Marlin/Configuration_adv.h | 3 ++- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 26 ++++++++++++--------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 1 - Marlin/src/pins/ramps/pins_RAMPS_13.h | 1 + Marlin/src/pins/sam/pins_RAMPS4DUE.h | 1 + Marlin/src/pins/sam/pins_RAMPS_DUO.h | 1 + Marlin/src/pins/sam/pins_RAMPS_SMART.h | 1 - 7 files changed, 20 insertions(+), 14 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fc3ce9eea2..3d66ce72ff 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1259,7 +1259,8 @@ // Show SD percentage next to the progress bar //#define DOGM_SD_PERCENT - // Enable to save many cycles by drawing a hollow frame on the Info Screen + // Save many cycles by drawing a hollow frame or no frame on the Info Screen + //#define XYZ_NO_FRAME #define XYZ_HOLLOW_FRAME // Enable to save many cycles by drawing a hollow frame on Menu Screens diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index d149a9345d..5fea16bf97 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -104,6 +104,7 @@ #endif #define PROGRESS_BAR_X 54 +#define PROGRESS_BAR_Y (EXTRAS_BASELINE + 2) #define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, const uint8_t ty) { @@ -597,7 +598,7 @@ void MarlinUI::draw_status_screen() { // if (PAGE_CONTAINS(49, 52)) - u8g.drawFrame(PROGRESS_BAR_X, 49, PROGRESS_BAR_WIDTH, 4); + u8g.drawFrame(PROGRESS_BAR_X, PROGRESS_BAR_Y, PROGRESS_BAR_WIDTH, 4); // // Progress bar solid part @@ -638,7 +639,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(DOGM_SD_PERCENT) if (progress_string[0]) { - lcd_put_u8str(55, 48, progress_string); // Percent complete + lcd_put_u8str(55, EXTRAS_BASELINE, progress_string); // Percent complete lcd_put_wchar('%'); } #endif @@ -665,7 +666,7 @@ void MarlinUI::draw_status_screen() { // XYZ Coordinates // - #if ENABLED(XYZ_HOLLOW_FRAME) + #if EITHER(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) #define XYZ_FRAME_TOP 29 #define XYZ_FRAME_HEIGHT INFO_FONT_ASCENT + 3 #else @@ -675,15 +676,17 @@ void MarlinUI::draw_status_screen() { if (PAGE_CONTAINS(XYZ_FRAME_TOP, XYZ_FRAME_TOP + XYZ_FRAME_HEIGHT - 1)) { - #if ENABLED(XYZ_HOLLOW_FRAME) - u8g.drawFrame(0, XYZ_FRAME_TOP, LCD_PIXEL_WIDTH, XYZ_FRAME_HEIGHT); // 8: 29-40 7: 29-39 - #else - u8g.drawBox(0, XYZ_FRAME_TOP, LCD_PIXEL_WIDTH, XYZ_FRAME_HEIGHT); // 8: 30-39 7: 30-37 + #if DISABLED(XYZ_NO_FRAME) + #if ENABLED(XYZ_HOLLOW_FRAME) + u8g.drawFrame(0, XYZ_FRAME_TOP, LCD_PIXEL_WIDTH, XYZ_FRAME_HEIGHT); // 8: 29-40 7: 29-39 + #else + u8g.drawBox(0, XYZ_FRAME_TOP, LCD_PIXEL_WIDTH, XYZ_FRAME_HEIGHT); // 8: 30-39 7: 30-37 + #endif #endif if (PAGE_CONTAINS(XYZ_BASELINE - (INFO_FONT_ASCENT - 1), XYZ_BASELINE)) { - #if DISABLED(XYZ_HOLLOW_FRAME) + #if NONE(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) u8g.setColorIndex(0); // white on black #endif @@ -722,7 +725,7 @@ void MarlinUI::draw_status_screen() { _draw_axis_value(Z_AXIS, zstring, blink); - #if DISABLED(XYZ_HOLLOW_FRAME) + #if NONE(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) u8g.setColorIndex(1); // black on white #endif } @@ -770,10 +773,11 @@ void MarlinUI::draw_status_screen() { lcd_put_wchar(':'); lcd_put_u8str(mstring); lcd_put_wchar('%'); + return; } - else #endif - draw_status_message(blink); + + draw_status_message(blink); } } diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 391f475fef..4f4927f312 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -26,7 +26,6 @@ // // Limit Switches // - #define X_MIN_PIN P1_29 #define X_MAX_PIN P1_28 #define Y_MIN_PIN P1_27 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_13.h b/Marlin/src/pins/ramps/pins_RAMPS_13.h index 1eb883f4db..3e3f149937 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_13.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_13.h @@ -39,4 +39,5 @@ #endif #define IS_RAMPS_13 + #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/sam/pins_RAMPS4DUE.h b/Marlin/src/pins/sam/pins_RAMPS4DUE.h index 21a2055967..5cb4f75f27 100644 --- a/Marlin/src/pins/sam/pins_RAMPS4DUE.h +++ b/Marlin/src/pins/sam/pins_RAMPS4DUE.h @@ -44,6 +44,7 @@ #endif #define BOARD_INFO_NAME "RAMPS4DUE" + #define IS_RAMPS4DUE // diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index 916dbf6430..5da157baf2 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -50,6 +50,7 @@ #define BOARD_INFO_NAME "RAMPS Duo" #define IS_RAMPS_DUO + #include "../ramps/pins_RAMPS.h" // diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 0fd4a6b3ea..d82c69b254 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -65,7 +65,6 @@ #endif #define BOARD_INFO_NAME "RAMPS-SMART" - #define IS_RAMPS_SMART #include "../ramps/pins_RAMPS.h" From 5e23fd6ef1bfda86fb79ede937b62e45085ea590 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 4 May 2020 00:03:16 +0000 Subject: [PATCH 0375/1454] [cron] Bump distribution date (2020-05-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 35b25540d9..94ef9d6439 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-03" + #define STRING_DISTRIBUTION_DATE "2020-05-04" #endif /** From 2a959cde6fdd5edea5c9ff20d613db024eb96749 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 4 May 2020 12:57:12 -0600 Subject: [PATCH 0376/1454] Fix undefined/unused, Touch UI (#17874) --- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 1 + .../extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp | 5 ++++- .../lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp | 4 +++- .../lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 5 +---- Marlin/src/module/motion.cpp | 2 ++ Marlin/src/sd/cardreader.h | 3 ++- 7 files changed, 14 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index 736f7050e8..aaf2ccc207 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -123,6 +123,7 @@ bool MarlinUI::detected() { return true; } custom_start_bmp #endif ; + TERN(CUSTOM_BOOTSCREEN_ANIMATED,,UNUSED(frame)); u8g.drawBitmapP(left, top, CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH, CUSTOM_BOOTSCREEN_BMPHEIGHT, bmp); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 583b03911d..fe8771e146 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -32,7 +32,10 @@ namespace FTDI { #ifdef CLCD_SPI_BUS SPIClass EVE_SPI(CLCD_SPI_BUS); #endif - SPISettings SPI::spi_settings(SPI_FREQUENCY, MSBFIRST, SPI_MODE0); + #ifndef CLCD_HW_SPI_SPEED + #define CLCD_HW_SPI_SPEED 8000000 >> SPI_SPEED + #endif + SPISettings SPI::spi_settings(CLCD_HW_SPI_SPEED, MSBFIRST, SPI_MODE0); #endif void SPI::spi_init() { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp index 9689170077..7e88b7883a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp @@ -78,7 +78,9 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - TERN_(LCD_TIMEOUT_TO_STATUS, last_interaction = millis()); + #if LCD_TIMEOUT_TO_STATUS + last_interaction = millis(); + #endif } #if LCD_TIMEOUT_TO_STATUS diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp index 4510c93416..a20e11b31d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp @@ -96,7 +96,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { #else PIN_DISABLED(1, 4, GET_TEXT_F(MSG_RUNOUT_1), FIL_RUNOUT) #endif - #if ENABLED(FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) + #if ENABLED(FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) && EXTRUDERS > 1 PIN_ENABLED (3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2, FIL_RUNOUT_INVERTING) #else PIN_DISABLED(3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 2b72eca047..937a435d7d 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -54,6 +54,7 @@ #include "../../module/printcounter.h" #include "../../libs/duration_t.h" #include "../../HAL/shared/Delay.h" +#include "../../sd/cardreader.h" #if ENABLED(PRINTCOUNTER) #include "../../core/utility.h" @@ -68,10 +69,6 @@ #include "../../feature/e_parser.h" #endif -#if ENABLED(SDSUPPORT) - #include "../../sd/cardreader.h" -#endif - #if HAS_TRINAMIC_CONFIG #include "../../feature/tmc_util.h" #include "../../module/stepper/indirection.h" diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 04f8507031..27e3fa125d 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1514,6 +1514,8 @@ void backout_to_tmc_homing_phase(const AxisEnum axis) { // retrace by the amount computed in mmDelta. do_homing_move(axis, mmDelta, get_homing_bump_feedrate(axis)); } + #else + UNUSED(axis); #endif } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index acaabf2deb..f783f96ca7 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -23,6 +23,8 @@ #include "../inc/MarlinConfig.h" +#define IFSD(A,B) TERN(SDSUPPORT,A,B) + #if ENABLED(SDSUPPORT) #if BOTH(SDCARD_SORT_ALPHA, SDSORT_DYNAMIC_RAM) @@ -30,7 +32,6 @@ #endif #define SD_ORDER(N,C) (TERN(SDCARD_RATHERRECENTFIRST, C - 1 - (N), N)) -#define IFSD(A,B) TERN(SDSUPPORT,A,B) #define MAX_DIR_DEPTH 10 // Maximum folder depth #define MAXDIRNAMELENGTH 8 // DOS folder name size From 714df3001ae3130ecf1bd639a6d5707fc3e08959 Mon Sep 17 00:00:00 2001 From: MigueKun <37217942+kunpoolsion@users.noreply.github.com> Date: Mon, 4 May 2020 20:59:22 +0200 Subject: [PATCH 0377/1454] Fix Fysetc S6 PIO env (#17865) --- platformio.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index dad4beb143..36d943d670 100644 --- a/platformio.ini +++ b/platformio.ini @@ -684,10 +684,11 @@ build_flags = ${common.build_flags} -DTARGET_STM32F4 -std=gnu++14 -DVECT_TAB_OFFSET=0x10000 -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED -DUSBD_VID=0x0483 '-DUSB_PRODUCT="FYSETC_S6"' + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py src_filter = ${common.default_src_filter} + -lib_ignore = Arduino-L6470 +lib_ignore = Arduino-L6470, SoftwareSerial debug_tool = stlink #upload_protocol = stlink upload_protocol = serial From 1c32f1003978417c7fc2b248e6a561effef88c55 Mon Sep 17 00:00:00 2001 From: mojocorp Date: Mon, 4 May 2020 21:03:01 +0200 Subject: [PATCH 0378/1454] Fix Malyan LCD crash bug (#17855) --- Marlin/src/lcd/extui_malyan_lcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 887738b3a6..63b52e2332 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -378,12 +378,12 @@ void parse_lcd_byte(const byte b) { || (!is_lcd && c == '\n') // LF on a G-code command ) { inbound_buffer[inbound_count] = '\0'; // Reset before processing - parsing = 0; // Unflag and... inbound_count = 0; // Reset buffer index if (parsing == 1) process_lcd_command(inbound_buffer); // Handle the LCD command else queue.enqueue_one_now(inbound_buffer); // Handle the G-code command + parsing = 0; // Unflag and... } else if (inbound_count < MAX_CURLY_COMMAND - 2) inbound_buffer[inbound_count++] = is_lcd ? c : b; // Buffer while space remains From 38d1587091ba7b7258a194f6ad950e80c1490225 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 14:37:43 -0500 Subject: [PATCH 0379/1454] Malyan M200 V2 (#17840) --- Marlin/src/core/boards.h | 51 ++++++++++--------- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 10 ++-- Marlin/src/lcd/extui/ui_api.cpp | 4 +- Marlin/src/lcd/extui_dgus_lcd.cpp | 13 +++-- Marlin/src/lcd/extui_malyan_lcd.cpp | 48 +++++++++++++---- Marlin/src/lcd/language/language_en.h | 4 ++ Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h | 31 +++++++++++ Marlin/src/pins/stm32f1/pins_MALYAN_M200.h | 4 +- .../share/PlatformIO/boards/malyanM200.json | 1 - .../share/PlatformIO/boards/malyanM200v2.json | 2 +- platformio.ini | 18 +++++-- 12 files changed, 132 insertions(+), 56 deletions(-) create mode 100644 Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 82a969b71a..22e64f7ccf 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -277,31 +277,32 @@ #define BOARD_STM32F103RE 4000 // STM32F103RE Libmaple-based STM32F1 controller #define BOARD_MALYAN_M200 4001 // STM32C8T6 Libmaple-based STM32F1 controller -#define BOARD_STM3R_MINI 4002 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_GTM32_PRO_VB 4003 // STM32F103VET6 controller -#define BOARD_MORPHEUS 4004 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller -#define BOARD_CHITU3D 4005 // Chitu3D (STM32F103RET6) -#define BOARD_MKS_ROBIN 4006 // MKS Robin (STM32F103ZET6) -#define BOARD_MKS_ROBIN_MINI 4007 // MKS Robin Mini (STM32F103VET6) -#define BOARD_MKS_ROBIN_NANO 4008 // MKS Robin Nano (STM32F103VET6) -#define BOARD_MKS_ROBIN_LITE 4009 // MKS Robin Lite/Lite2 (STM32F103RCT6) -#define BOARD_MKS_ROBIN_LITE3 4010 // MKS Robin Lite3 (STM32F103RCT6) -#define BOARD_MKS_ROBIN_PRO 4011 // MKS Robin Pro (STM32F103ZET6) -#define BOARD_BTT_SKR_MINI_V1_1 4012 // BigTreeTech SKR Mini v1.1 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_0 4013 // BigTreeTech SKR Mini E3 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_2 4014 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4015 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4016 // JGAurora A5S A1 (STM32F103ZET6) -#define BOARD_FYSETC_AIO_II 4017 // FYSETC AIO_II -#define BOARD_FYSETC_CHEETAH 4018 // FYSETC Cheetah -#define BOARD_FYSETC_CHEETAH_V12 4019 // FYSETC Cheetah V1.2 -#define BOARD_LONGER3D_LK 4020 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 -#define BOARD_GTM32_MINI 4021 // STM32F103VET6 controller -#define BOARD_GTM32_MINI_A30 4022 // STM32F103VET6 controller -#define BOARD_GTM32_REV_B 4023 // STM32F103VET6 controller -#define BOARD_MKS_ROBIN_E3D 4024 // MKS Robin E3D(STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3 4025 // MKS Robin E3(STM32F103RCT6) -#define BOARD_MALYAN_M300 4026 // STM32F070-based delta +#define BOARD_MALYAN_M200_V2 4002 // STM32F070RB Libmaple-based STM32F0 controller +#define BOARD_STM3R_MINI 4003 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_GTM32_PRO_VB 4004 // STM32F103VET6 controller +#define BOARD_MORPHEUS 4005 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller +#define BOARD_CHITU3D 4006 // Chitu3D (STM32F103RET6) +#define BOARD_MKS_ROBIN 4007 // MKS Robin (STM32F103ZET6) +#define BOARD_MKS_ROBIN_MINI 4008 // MKS Robin Mini (STM32F103VET6) +#define BOARD_MKS_ROBIN_NANO 4009 // MKS Robin Nano (STM32F103VET6) +#define BOARD_MKS_ROBIN_LITE 4010 // MKS Robin Lite/Lite2 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_LITE3 4011 // MKS Robin Lite3 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_PRO 4012 // MKS Robin Pro (STM32F103ZET6) +#define BOARD_BTT_SKR_MINI_V1_1 4013 // BigTreeTech SKR Mini v1.1 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_0 4014 // BigTreeTech SKR Mini E3 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_2 4015 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 4016 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 4017 // JGAurora A5S A1 (STM32F103ZET6) +#define BOARD_FYSETC_AIO_II 4018 // FYSETC AIO_II +#define BOARD_FYSETC_CHEETAH 4019 // FYSETC Cheetah +#define BOARD_FYSETC_CHEETAH_V12 4020 // FYSETC Cheetah V1.2 +#define BOARD_LONGER3D_LK 4021 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 +#define BOARD_GTM32_MINI 4022 // STM32F103VET6 controller +#define BOARD_GTM32_MINI_A30 4023 // STM32F103VET6 controller +#define BOARD_GTM32_REV_B 4024 // STM32F103VET6 controller +#define BOARD_MKS_ROBIN_E3D 4025 // MKS Robin E3D(STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3 4026 // MKS Robin E3(STM32F103RCT6) +#define BOARD_MALYAN_M300 4027 // STM32F070-based delta // // ARM Cortex-M4F diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index e4dbf7b360..6e9595e099 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -150,19 +150,19 @@ namespace ExtUI { #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { case PID_BAD_EXTRUDER_NUM: - StatusScreen::setStatusMessage(STR_PID_BAD_EXTRUDER_NUM); + StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); break; case PID_TEMP_TOO_HIGH: - StatusScreen::setStatusMessage(STR_PID_TEMP_TOO_HIGH); + StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); break; case PID_TUNING_TIMEOUT: - StatusScreen::setStatusMessage(STR_PID_TIMEOUT); + StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); break; case PID_DONE: - StatusScreen::setStatusMessage(STR_PID_AUTOTUNE_FINISHED); + StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); break; } GOTO_SCREEN(StatusScreen); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 937a435d7d..95f630f7ec 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -330,8 +330,8 @@ namespace ExtUI { // Delta limits XY based on the current offset from center // This assumes the center is 0,0 #if ENABLED(DELTA) - if (axis != Z_AXIS) { - max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); // (Y_AXIS - axis) == the other axis + if (axis != Z) { + max = SQRT(sq(float(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y - axis])); // (Y - axis) == the other axis min = -max; } #endif diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index c29bc5a114..56308f08d6 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -45,7 +45,7 @@ namespace ExtUI { void onIdle() { ScreenHandler.loop(); } - void onPrinterKilled(PGM_P error, PGM_P component) { + void onPrinterKilled(PGM_P const error, PGM_P const component) { ScreenHandler.sendinfoscreen(GET_TEXT(MSG_HALTED), error, NUL_STR, GET_TEXT(MSG_PLEASE_RESET), true, true, true, true); ScreenHandler.GotoScreen(DGUSLCD_SCREEN_KILL); while (!ScreenHandler.loop()); // Wait while anything is left to be sent @@ -127,19 +127,18 @@ namespace ExtUI { #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - SERIAL_ECHOLNPAIR("onPidTuning:",rst); - switch(rst) { + switch (rst) { case PID_BAD_EXTRUDER_NUM: - ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_BAD_EXTRUDER_NUM)); + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); break; case PID_TEMP_TOO_HIGH: - ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_TEMP_TOO_HIGH)); + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); break; case PID_TUNING_TIMEOUT: - ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_TIMEOUT)); + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); break; case PID_DONE: - ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_AUTOTUNE_FINISHED)); + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); break; } ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 63b52e2332..85101ae8d9 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -97,6 +97,18 @@ void write_to_lcd(const char * const message) { LCD_SERIAL.Print::write(encoded_message, message_length); } +// {E:} is for error states. +void set_lcd_error_P(PGM_P const error, PGM_P const component=nullptr) { + write_to_lcd_P(PSTR("{E:")); + write_to_lcd_P(error); + if (component) { + write_to_lcd_P(PSTR(" ")); + write_to_lcd_P(component); + } + write_to_lcd_P(PSTR("}")); +} + + /** * Process an LCD 'C' command. * These are currently all temperature commands @@ -465,15 +477,33 @@ namespace ExtUI { #endif } - // {E:} is for error states. - void onPrinterKilled(PGM_P error, PGM_P component) { - write_to_lcd_P(PSTR("{E:")); - write_to_lcd_P(error); - write_to_lcd_P(PSTR(" ")); - write_to_lcd_P(component); - write_to_lcd_P("}"); + void onPrinterKilled(PGM_P const error, PGM_P const component) { + set_lcd_error_P(error, component); } + #if HAS_PID_HEATING + + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + switch (rst) { + case PID_BAD_EXTRUDER_NUM: + set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + break; + case PID_TEMP_TOO_HIGH: + set_lcd_error_P(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + break; + case PID_TUNING_TIMEOUT: + set_lcd_error_P(GET_TEXT(MSG_PID_TIMEOUT)); + break; + case PID_DONE: + set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + break; + } + } + + #endif + void onPrintTimerStarted() { write_to_lcd_P(PSTR("{SYS:BUILD}")); } void onPrintTimerPaused() {} void onPrintTimerStopped() { write_to_lcd_P(PSTR("{TQ:100}")); } @@ -500,10 +530,6 @@ namespace ExtUI { #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() {} #endif - - #if HAS_PID_HEATING - void onPidTuning(const result_t rst) {} - #endif } #endif // MALYAN_LCD diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f9fb84cc80..8249dba743 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -266,6 +266,10 @@ namespace Language_en { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Off"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index dc42d80706..3ce761c6cf 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -469,6 +469,8 @@ // // STM32 ARM Cortex-M0 // +#elif MB(MALYAN_M200_V2) + #include "stm32f0/pins_MALYAN_M200_V2.h" // STM32F0 env:STM32F070RB_malyan #elif MB(MALYAN_M300) #include "stm32f0/pins_MALYAN_M300.h" // STM32F070 env:malyan_M300 diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h new file mode 100644 index 0000000000..e8b4eed2fd --- /dev/null +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h @@ -0,0 +1,31 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#pragma once + +#ifndef STM32F0xx + #error "Oops! Select an STM32F0 board in your IDE." +#endif + +#define BOARD_INFO_NAME "Malyan M200 V2" + +#include "../stm32f1/pins_MALYAN_M200.h" diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 87f323dfa5..6e96df45c1 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -29,7 +29,9 @@ #error "Oops! Select an STM32 board in your IDE." #endif -#define BOARD_INFO_NAME "Malyan M200" +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Malyan M200" +#endif // Assume Flash EEPROM #if NO_EEPROM_SELECTED diff --git a/buildroot/share/PlatformIO/boards/malyanM200.json b/buildroot/share/PlatformIO/boards/malyanM200.json index dc0cf51f9e..bd783fe899 100644 --- a/buildroot/share/PlatformIO/boards/malyanM200.json +++ b/buildroot/share/PlatformIO/boards/malyanM200.json @@ -11,7 +11,6 @@ "ldscript": "jtagOffset.ld", "mcu": "stm32f103cb", "variant": "malyanM200", - "genericvariant" : "MALYAN_M200_V1", "vec_tab_addr": "0x8002000" }, "debug": { diff --git a/buildroot/share/PlatformIO/boards/malyanM200v2.json b/buildroot/share/PlatformIO/boards/malyanM200v2.json index 0d2090a93b..9e301ee79f 100644 --- a/buildroot/share/PlatformIO/boards/malyanM200v2.json +++ b/buildroot/share/PlatformIO/boards/malyanM200v2.json @@ -4,7 +4,7 @@ "extra_flags": "-DSTM32F070xB", "f_cpu": "48000000L", "mcu": "stm32f070rbt6", - "genericvariant" : "MALYAN_M200_V2", + "variant": "MALYANM200_F070CB", "vec_tab_addr": "0x8002000" }, "debug": { diff --git a/platformio.ini b/platformio.ini index 36d943d670..163c6b7419 100644 --- a/platformio.ini +++ b/platformio.ini @@ -605,10 +605,22 @@ lib_ignore = Adafruit NeoPixel, SPI [env:STM32F103CB_malyan] platform = ststm32 board = malyanM200 -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -D MOTHERBOARD="BOARD_MALYAN_M200" -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel, LiquidCrystal, LiquidTWI2, TMCStepper, U8glib-HAL, SPI +lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL, SPI + +# +# Malyan M200 v2 (STM32F070RB) +# +[env:STM32F070RB_malyan] +platform = ststm32 +board = malyanM200v2 +build_flags = -DSTM32F0xx -DUSBCON -DUSBD_VID=0x0483 '-DUSB_MANUFACTURER="Unknown"' '-DUSB_PRODUCT="ARMED_V1"' -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED + -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -std=gnu11 -std=gnu++11 + -IMarlin/src/HAL/STM32 +src_filter = ${common.default_src_filter} + +lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL # # Malyan M300 (STM32F070CB) @@ -620,7 +632,7 @@ build_flags = ${common.build_flags} -DUSBCON -DUSBD_VID=0x0483 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"MALYAN_M300\"" -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED src_filter = ${common.default_src_filter} + -lib_ignore = U8glib, LiquidCrystal_I2C, LiquidCrystal, NewliquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, Servo(STM32F1), TMC26XStepper, U8glib-HAL +lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL # # Chitu boards like Tronxy X5s (STM32F103ZET6) From ebe8f2c605b6d07d067db3e013cb26741bf1e207 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C5=A0t=C4=9Bp=C3=A1n=20Daleck=C3=BD?= <36531759+daleckystepan@users.noreply.github.com> Date: Mon, 4 May 2020 21:39:51 +0200 Subject: [PATCH 0380/1454] Fix acosx condition (#17846) --- Marlin/src/module/planner.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 54714715f2..bb9e7b92fe 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2311,7 +2311,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, t = neg * junction_cos_theta; // If angle is greater than 135 degrees (octagon), find speed for approximate arc - if (t < -0.7071067812f) { + if (t > 0.7071067812f) { #if ENABLED(JD_USE_MATH_ACOS) @@ -2358,7 +2358,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, 4.85301876f, 6.77019119f, 9.50873947f, 13.4009094f, 18.9188652f, 26.7320709f, 37.7884521f, 53.4292908f, 75.5522461f, 0.0f }; - const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(int16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; + const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(uint16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; float junction_theta = t * pgm_read_float(&jd_lut_k[idx]) + pgm_read_float(&jd_lut_b[idx]); if (neg > 0) junction_theta = RADIANS(180) - junction_theta; From 4c4be32ad7c8096ccda1b12ef1e1f8fb8d57f005 Mon Sep 17 00:00:00 2001 From: randellhodges Date: Mon, 4 May 2020 14:54:33 -0500 Subject: [PATCH 0381/1454] LPC176x requires USE_SHARED_EEPROM (#17858) --- Marlin/src/HAL/LPC1768/inc/Conditionals_post.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index 24ff12cf19..9b76c25102 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -23,4 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION +#elif EITHER(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 #endif From cd8e6a1ad75ae80974fb61348eb00a0206d723f0 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 4 May 2020 13:40:23 -0700 Subject: [PATCH 0382/1454] Git attributes for UNIX line endings (#17842) --- buildroot/bin/.gitattributes | 1 + buildroot/share/tests/.gitattributes | 1 + 2 files changed, 2 insertions(+) create mode 100644 buildroot/bin/.gitattributes create mode 100644 buildroot/share/tests/.gitattributes diff --git a/buildroot/bin/.gitattributes b/buildroot/bin/.gitattributes new file mode 100644 index 0000000000..6313b56c57 --- /dev/null +++ b/buildroot/bin/.gitattributes @@ -0,0 +1 @@ +* text=auto eol=lf diff --git a/buildroot/share/tests/.gitattributes b/buildroot/share/tests/.gitattributes new file mode 100644 index 0000000000..6313b56c57 --- /dev/null +++ b/buildroot/share/tests/.gitattributes @@ -0,0 +1 @@ +* text=auto eol=lf From 2efe28ca598f8d6fb6b17a2c5d29daac79d89dcb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 2 May 2020 23:26:12 -0500 Subject: [PATCH 0383/1454] Minor conditional clean --- Marlin/src/inc/Conditionals_LCD.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index ab8b812f55..e6c671f713 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -335,9 +335,7 @@ #endif #if ENABLED(ULTIPANEL) #define IS_ULTRA_LCD - #ifndef NEWPANEL - #define NEWPANEL - #endif + #define NEWPANEL #endif #if ENABLED(IS_ULTRA_LCD) From b8947ac8a5182b6b54165fb6ddc4177efb32091a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 15:13:37 -0500 Subject: [PATCH 0384/1454] More explicit junction/jerk math --- Marlin/src/module/planner.cpp | 6 +++--- Marlin/src/module/planner.h | 4 +--- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index bb9e7b92fe..6d2a0edc31 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2304,7 +2304,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec), sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive. - vmax_junction_sqr = JUNC_SQ(junction_acceleration, sin_theta_d2); + vmax_junction_sqr = junction_acceleration * junction_deviation_mm * sin_theta_d2 / (1.0f - sin_theta_d2); if (block->millimeters < 1) { const float neg = junction_cos_theta < 0 ? -1 : 1, @@ -2340,8 +2340,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * for (float t = 0; t <= 1; t += 0.0003f) { * const float e = acos(t) / approx(t); * if (isfinite(e)) { - * NOMORE(min, e); - * NOLESS(max, e); + * if (e < min) min = e; + * if (e > max) max = e; * } * } * fprintf(stderr, "%.9gf, ", (min + max) / 2); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ccc7faf706..05c5c44cee 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -838,11 +838,9 @@ class Planner { static void autotemp_update(); #endif - #define JUNC_SQ(N,ST) (junction_deviation_mm * (N) * (ST) / (1.0f - (ST))) - #if HAS_LINEAR_E_JERK FORCE_INLINE static void recalculate_max_e_jerk() { - #define GET_MAX_E_JERK(N) SQRT(JUNC_SQ(N,SQRT(0.5))) + #define GET_MAX_E_JERK(N) SQRT(junction_deviation_mm * (N) * SQRT(0.5) / (1.0f - SQRT(0.5))) #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(i, EXTRUDERS) max_e_jerk[i] = GET_MAX_E_JERK(settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]); From 9fe781ccafb6be8a8b86f6e24c7d19642862c962 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 16:37:20 -0500 Subject: [PATCH 0385/1454] Tweak powerloss info --- Marlin/src/feature/powerloss.cpp | 4 ++-- Marlin/src/feature/powerloss.h | 6 +----- 2 files changed, 3 insertions(+), 7 deletions(-) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 02a97e3436..0ba8737f2f 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -185,7 +185,7 @@ void PrintJobRecovery::save(const bool force/*=false*/) { #if EXTRUDERS > 1 for (int8_t e = 0; e < EXTRUDERS; e++) info.filament_size[e] = planner.filament_size[e]; #else - if (parser.volumetric_enabled) info.filament_size = planner.filament_size[active_extruder]; + if (parser.volumetric_enabled) info.filament_size[0] = planner.filament_size[active_extruder]; #endif #endif @@ -331,7 +331,7 @@ void PrintJobRecovery::resume() { } #else if (info.volumetric_enabled) { - dtostrf(info.filament_size, 1, 3, str_1); + dtostrf(info.filament_size[0], 1, 3, str_1); sprintf_P(cmd, PSTR("M200 D%s"), str_1); gcode.process_subcommands_now(cmd); } diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 71f9861e87..ff3fef80fa 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -61,11 +61,7 @@ typedef struct { #if DISABLED(NO_VOLUMETRICS) bool volumetric_enabled; - #if EXTRUDERS > 1 - float filament_size[EXTRUDERS]; - #else - float filament_size; - #endif + float filament_size[EXTRUDERS]; #endif #if HAS_HOTEND From 98196673aa1dca9ed936b94c16a23e8b4f607643 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 4 May 2020 16:19:49 -0600 Subject: [PATCH 0386/1454] Fix setStatusMessage calls (#17879) --- .../src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index 6e9595e099..9c0396f03b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -153,16 +153,16 @@ namespace ExtUI { //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { case PID_BAD_EXTRUDER_NUM: - StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_BAD_EXTRUDER_NUM)); break; case PID_TEMP_TOO_HIGH: - StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); break; case PID_TUNING_TIMEOUT: - StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); break; case PID_DONE: - StatusScreen::setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); break; } GOTO_SCREEN(StatusScreen); From d571a4d389c60d8d8768c769da3369627197cd88 Mon Sep 17 00:00:00 2001 From: Mathias Rasmussen Date: Tue, 5 May 2020 00:23:35 +0200 Subject: [PATCH 0387/1454] Relax bed cooling safety check (#17877) --- Marlin/src/module/temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index a456aa8af3..7518e0ef2c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3074,7 +3074,7 @@ void Temperature::tick() { #if HAS_HEATED_BED #ifndef MIN_COOLING_SLOPE_DEG_BED - #define MIN_COOLING_SLOPE_DEG_BED 1.50 + #define MIN_COOLING_SLOPE_DEG_BED 1.00 #endif #ifndef MIN_COOLING_SLOPE_TIME_BED #define MIN_COOLING_SLOPE_TIME_BED 60 From c55475e8e7c7b389b30ca1d154618d73faba52ab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 19:01:54 -0500 Subject: [PATCH 0388/1454] Fix and combine JD condition --- Marlin/src/module/planner.cpp | 134 +++++++++++++++++----------------- 1 file changed, 67 insertions(+), 67 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 6d2a0edc31..ee357179c0 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2306,87 +2306,87 @@ bool Planner::_populate_block(block_t * const block, bool split_move, vmax_junction_sqr = junction_acceleration * junction_deviation_mm * sin_theta_d2 / (1.0f - sin_theta_d2); - if (block->millimeters < 1) { - const float neg = junction_cos_theta < 0 ? -1 : 1, - t = neg * junction_cos_theta; + // For small moves with >135° junction (octagon) find speed for approximate arc + if (block->millimeters < 1 && junction_cos_theta < -0.7071067812f) { - // If angle is greater than 135 degrees (octagon), find speed for approximate arc - if (t > 0.7071067812f) { + #if ENABLED(JD_USE_MATH_ACOS) - #if ENABLED(JD_USE_MATH_ACOS) + #error "TODO: Inline maths with the MCU / FPU." - #error "TODO: Inline maths with the MCU / FPU." + #elif ENABLED(JD_USE_LOOKUP_TABLE) - #elif ENABLED(JD_USE_LOOKUP_TABLE) + // Fast acos approximation (max. error +-0.01 rads) + // Based on LUT table and linear interpolation - // Fast acos approximation (max. error +-0.01 rads) - // Based on LUT table and linear interpolation + /** + * // Generate the JD Lookup Table + * constexpr float c = 1.00751317f; // Correction factor to center error around 0 + * for (int i = 0; i < jd_lut_count - 1; ++i) { + * const float x0 = (sq(i) - 1) / sq(i), + * y0 = acos(x0) * (i ? c : 1), + * x1 = 0.5 * x0 + 0.5, + * y1 = acos(x1) * c; + * jd_lut_k[i] = (y0 - y1) / (x0 - x1); + * jd_lut_b[i] = (y1 * x0 - y0 * x1) / (x0 - x1); + * } + * jd_lut_k[jd_lut_count - 1] = jd_lut_b[jd_lut_count - 1] = 0; + * + * // Compute correction factor (Set c to 1.0f first!) + * float min = INFINITY, max = -min; + * for (float t = 0; t <= 1; t += 0.0003f) { + * const float e = acos(t) / approx(t); + * if (isfinite(e)) { + * if (e < min) min = e; + * if (e > max) max = e; + * } + * } + * fprintf(stderr, "%.9gf, ", (min + max) / 2); + */ + static constexpr int16_t jd_lut_count = 15; + static constexpr uint16_t jd_lut_tll = 1 << jd_lut_count; + static constexpr int16_t jd_lut_tll0 = __builtin_clz(jd_lut_tll) + 1; // i.e., 16 - jd_lut_count + static constexpr float jd_lut_k[jd_lut_count] PROGMEM = { + -1.03146219f, -1.30760407f, -1.75205469f, -2.41705418f, -3.37768555f, + -4.74888229f, -6.69648552f, -9.45659828f, -13.3640289f, -18.8927879f, + -26.7136307f, -37.7754059f, -53.4200745f, -75.5457306f, 0.0f }; + static constexpr float jd_lut_b[jd_lut_count] PROGMEM = { + 1.57079637f, 1.70886743f, 2.04220533f, 2.62408018f, 3.52467203f, + 4.85301876f, 6.77019119f, 9.50873947f, 13.4009094f, 18.9188652f, + 26.7320709f, 37.7884521f, 53.4292908f, 75.5522461f, 0.0f }; - /** - * // Generate the JD Lookup Table - * constexpr float c = 1.00751317f; // Correction factor to center error around 0 - * for (int i = 0; i < jd_lut_count - 1; ++i) { - * const float x0 = (sq(i) - 1) / sq(i), - * y0 = acos(x0) * (i ? c : 1), - * x1 = 0.5 * x0 + 0.5, - * y1 = acos(x1) * c; - * jd_lut_k[i] = (y0 - y1) / (x0 - x1); - * jd_lut_b[i] = (y1 * x0 - y0 * x1) / (x0 - x1); - * } - * jd_lut_k[jd_lut_count - 1] = jd_lut_b[jd_lut_count - 1] = 0; - * - * // Compute correction factor (Set c to 1.0f first!) - * float min = INFINITY, max = -min; - * for (float t = 0; t <= 1; t += 0.0003f) { - * const float e = acos(t) / approx(t); - * if (isfinite(e)) { - * if (e < min) min = e; - * if (e > max) max = e; - * } - * } - * fprintf(stderr, "%.9gf, ", (min + max) / 2); - */ - static constexpr int16_t jd_lut_count = 15; - static constexpr uint16_t jd_lut_tll = 1 << jd_lut_count; - static constexpr int16_t jd_lut_tll0 = __builtin_clz(jd_lut_tll) + 1; // i.e., 16 - jd_lut_count - static constexpr float jd_lut_k[jd_lut_count] PROGMEM = { - -1.03146219f, -1.30760407f, -1.75205469f, -2.41705418f, -3.37768555f, - -4.74888229f, -6.69648552f, -9.45659828f, -13.3640289f, -18.8927879f, - -26.7136307f, -37.7754059f, -53.4200745f, -75.5457306f, 0.0f }; - static constexpr float jd_lut_b[jd_lut_count] PROGMEM = { - 1.57079637f, 1.70886743f, 2.04220533f, 2.62408018f, 3.52467203f, - 4.85301876f, 6.77019119f, 9.50873947f, 13.4009094f, 18.9188652f, - 26.7320709f, 37.7884521f, 53.4292908f, 75.5522461f, 0.0f }; + const float neg = junction_cos_theta < 0 ? -1 : 1, + t = neg * junction_cos_theta; - const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(uint16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; + const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(uint16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; - float junction_theta = t * pgm_read_float(&jd_lut_k[idx]) + pgm_read_float(&jd_lut_b[idx]); - if (neg > 0) junction_theta = RADIANS(180) - junction_theta; + float junction_theta = t * pgm_read_float(&jd_lut_k[idx]) + pgm_read_float(&jd_lut_b[idx]); + if (neg > 0) junction_theta = RADIANS(180) - junction_theta; // acos(-t) - #else + #else - // Fast acos(-t) approximation (max. error +-0.033rad = 1.89°) - // Based on MinMax polynomial published by W. Randolph Franklin, see - // https://wrf.ecse.rpi.edu/Research/Short_Notes/arcsin/onlyelem.html - // acos( t) = pi / 2 - asin(x) - // acos(-t) = pi - acos(t) ... pi / 2 + asin(x) + // Fast acos(-t) approximation (max. error +-0.033rad = 1.89°) + // Based on MinMax polynomial published by W. Randolph Franklin, see + // https://wrf.ecse.rpi.edu/Research/Short_Notes/arcsin/onlyelem.html + // acos( t) = pi / 2 - asin(x) + // acos(-t) = pi - acos(t) ... pi / 2 + asin(x) - const float asinx = 0.032843707f - + t * (-1.451838349f - + t * ( 29.66153956f - + t * (-131.1123477f - + t * ( 262.8130562f - + t * (-242.7199627f - + t * ( 84.31466202f ) ))))), - junction_theta = RADIANS(90) + neg * asinx; // acos(-t) + const float neg = junction_cos_theta < 0 ? -1 : 1, + t = neg * junction_cos_theta, + asinx = 0.032843707f + + t * (-1.451838349f + + t * ( 29.66153956f + + t * (-131.1123477f + + t * ( 262.8130562f + + t * (-242.7199627f + + t * ( 84.31466202f ) ))))), + junction_theta = RADIANS(90) + neg * asinx; // acos(-t) - // NOTE: junction_theta bottoms out at 0.033 which avoids divide by 0. + // NOTE: junction_theta bottoms out at 0.033 which avoids divide by 0. - #endif + #endif - const float limit_sqr = (block->millimeters * junction_acceleration) / junction_theta; - NOMORE(vmax_junction_sqr, limit_sqr); - } + const float limit_sqr = (block->millimeters * junction_acceleration) / junction_theta; + NOMORE(vmax_junction_sqr, limit_sqr); } } From 7655620fd0ba3c2f3d38eb71d5c0d7fa7a56c181 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 5 May 2020 00:03:45 +0000 Subject: [PATCH 0389/1454] [cron] Bump distribution date (2020-05-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 94ef9d6439..e401b45b69 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-04" + #define STRING_DISTRIBUTION_DATE "2020-05-05" #endif /** From 0080305fa6b81340f30e7b05068c68def6136199 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 17:41:41 -0500 Subject: [PATCH 0390/1454] Tweaks to platformio.ini --- platformio.ini | 26 ++++++++++++-------------- 1 file changed, 12 insertions(+), 14 deletions(-) diff --git a/platformio.ini b/platformio.ini index 163c6b7419..9f77af1afc 100644 --- a/platformio.ini +++ b/platformio.ini @@ -629,8 +629,8 @@ lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-H platform = ststm32@>=6.1.0 board = malyanm300_f070cb build_flags = ${common.build_flags} - -DUSBCON -DUSBD_VID=0x0483 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"MALYAN_M300\"" - -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED + -DUSBCON -DUSBD_VID=0x0483 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"MALYAN_M300\"" + -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED src_filter = ${common.default_src_filter} + lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL @@ -656,10 +656,10 @@ platform = ststm32 board = STEVAL_STM32F401VE platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} - -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE - -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" - -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS - -IMarlin/src/HAL/STM32 + -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE + -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" + -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py @@ -715,10 +715,10 @@ platform = ststm32 board = blackSTM32F407VET6 platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} - -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE - -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\" - -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS - -IMarlin/src/HAL/STM32 + -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE + -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\" + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial @@ -749,7 +749,6 @@ debug_init_break = # [env:BIGTREE_GTR_V1_0] platform = ststm32@>=5.7.0 -framework = arduino platform_packages = framework-arduinoststm32@>=3.10700,<4 board = BigTree_SKR_Pro extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -766,7 +765,6 @@ lib_deps = Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/dev.zip lib_ignore = SoftwareSerial, SoftwareSerialM src_filter = ${common.default_src_filter} + -monitor_speed = 250000 # # BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) @@ -890,8 +888,8 @@ upload_protocol = dfu platform = ststm32 board = rumba32_f446ve build_flags = ${common.build_flags} - -DSTM32F4xx -DARDUINO_RUMBA32_F446VE -DARDUINO_ARCH_STM32 "-DBOARD_NAME=\"RUMBA32_F446VE\"" - -DSTM32F446xx -DUSBCON -DUSBD_VID=0x8000 + -DSTM32F4xx -DARDUINO_RUMBA32_F446VE -DARDUINO_ARCH_STM32 "-DBOARD_NAME=\"RUMBA32_F446VE\"" + -DSTM32F446xx -DUSBCON -DUSBD_VID=0x8000 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"RUMBA32_F446VE\"" -DHAL_PCD_MODULE_ENABLED From bab37dcfaee9943d6b266ba31494306212257dc6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 17:44:01 -0500 Subject: [PATCH 0391/1454] Add templated j_move_axis --- Marlin/src/lcd/extui_malyan_lcd.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 85101ae8d9..53cef9915b 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -206,18 +206,19 @@ void process_lcd_eb_command(const char* command) { * {J:E}{J:X+200}{J:E} * X, Y, Z, A (extruder) */ -void process_lcd_j_command(const char* command) { - auto move_axis = [command](const auto axis) { - const float dist = atof(command + 1) / 10.0; - ExtUI::setAxisPosition_mm(ExtUI::getAxisPosition_mm(axis) + dist, axis); - }; +template +void j_move_axis(const char* command, const T axis) { + const float dist = atof(command + 1) / 10.0; + ExtUI::setAxisPosition_mm(ExtUI::getAxisPosition_mm(axis) + dist, axis); +}; +void process_lcd_j_command(const char* command) { switch (command[0]) { case 'E': break; - case 'A': move_axis(ExtUI::extruder_t::E0); break; - case 'Y': move_axis(ExtUI::axis_t::Y); break; - case 'Z': move_axis(ExtUI::axis_t::Z); break; - case 'X': move_axis(ExtUI::axis_t::X); break; + case 'A': j_move_axis(command, ExtUI::extruder_t::E0); break; + case 'Y': j_move_axis(command, ExtUI::axis_t::Y); break; + case 'Z': j_move_axis(command, ExtUI::axis_t::Z); break; + case 'X': j_move_axis(command, ExtUI::axis_t::X); break; default: DEBUG_ECHOLNPAIR("UNKNOWN J COMMAND ", command); } } From 65104b7d78cfbcab93ca3c9a0b6f00eba5686575 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 17:47:24 -0500 Subject: [PATCH 0392/1454] Whitespace, M200 test label --- Marlin/src/core/boards.h | 4 ++-- buildroot/share/tests/STM32F103CB_malyan-tests | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 22e64f7ccf..826dc51d79 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -300,8 +300,8 @@ #define BOARD_GTM32_MINI 4022 // STM32F103VET6 controller #define BOARD_GTM32_MINI_A30 4023 // STM32F103VET6 controller #define BOARD_GTM32_REV_B 4024 // STM32F103VET6 controller -#define BOARD_MKS_ROBIN_E3D 4025 // MKS Robin E3D(STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3 4026 // MKS Robin E3(STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3D 4025 // MKS Robin E3D (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3 4026 // MKS Robin E3 (STM32F103RCT6) #define BOARD_MALYAN_M300 4027 // STM32F070-based delta // diff --git a/buildroot/share/tests/STM32F103CB_malyan-tests b/buildroot/share/tests/STM32F103CB_malyan-tests index fced4d5d24..e594cb43db 100644 --- a/buildroot/share/tests/STM32F103CB_malyan-tests +++ b/buildroot/share/tests/STM32F103CB_malyan-tests @@ -7,7 +7,7 @@ set -e use_example_configs Malyan/M200 -exec_test $1 $2 "Default Configuration" +exec_test $1 $2 "Malyan M200" # cleanup restore_configs From 97e47b4494cdfc3c48e70e377ca16c912fd5cc5a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 22:49:33 -0500 Subject: [PATCH 0393/1454] Wrap some macros --- Marlin/src/gcode/bedlevel/G26.cpp | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 9f94c2d9f0..4e2e94a714 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -582,7 +582,7 @@ void GcodeSuite::G26() { if (parser.seenval('H')) { g26_hotend_temp = parser.value_celsius(); - if (!WITHIN(g26_hotend_temp, 165, (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT))) { + if (!WITHIN(g26_hotend_temp, 165, (HEATER_0_MAXTEMP) - (HOTEND_OVERSHOOT))) { SERIAL_ECHOLNPGM("?Specified nozzle temperature not plausible."); return; } diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index 15ff541739..30efa39093 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -43,7 +43,7 @@ void GcodeSuite::M145() { int v; if (parser.seenval('H')) { v = parser.value_int(); - ui.preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - HOTEND_OVERSHOOT); + ui.preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP) - (HOTEND_OVERSHOOT)); } if (parser.seenval('F')) { v = parser.value_int(); From 90e1035e9bcb4dedee41e698a8923c71fbbaf060 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 23:07:54 -0500 Subject: [PATCH 0394/1454] Define max_e_jerk as array always --- Marlin/src/module/planner.cpp | 20 ++++++-------------- Marlin/src/module/planner.h | 12 ++++-------- 2 files changed, 10 insertions(+), 22 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index ee357179c0..2d68022c10 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -130,13 +130,13 @@ planner_settings_t Planner::settings; // Initialized by settings.load( uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 -float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step +float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step #if HAS_JUNCTION_DEVIATION - float Planner::junction_deviation_mm; // (mm) M205 J + float Planner::junction_deviation_mm; // (mm) M205 J #if ENABLED(LIN_ADVANCE) - float Planner::max_e_jerk // Calculated from junction_deviation_mm - TERN_(DISTINCT_E_FACTORS, [EXTRUDERS]); + float Planner::max_e_jerk // Calculated from junction_deviation_mm + [TERN(DISTINCT_E_FACTORS, EXTRUDERS, 1)]; #endif #endif @@ -2139,15 +2139,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(LIN_ADVANCE) - #if HAS_JUNCTION_DEVIATION - #if ENABLED(DISTINCT_E_FACTORS) - #define MAX_E_JERK max_e_jerk[extruder] - #else - #define MAX_E_JERK max_e_jerk - #endif - #else - #define MAX_E_JERK max_jerk.e - #endif + #define MAX_E_JERK(N) TERN(HAS_JUNCTION_DEVIATION, max_e_jerk[E_AXIS_N(N)], max_jerk.e) /** * @@ -2179,7 +2171,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (block->e_D_ratio > 3.0f) block->use_advance_lead = false; else { - const uint32_t max_accel_steps_per_s2 = MAX_E_JERK / (extruder_advance_K[active_extruder] * block->e_D_ratio) * steps_per_mm; + const uint32_t max_accel_steps_per_s2 = MAX_E_JERK(extruder) / (extruder_advance_K[active_extruder] * block->e_D_ratio) * steps_per_mm; if (TERN0(LA_DEBUG, accel > max_accel_steps_per_s2)) SERIAL_ECHOLNPGM("Acceleration limited."); NOMORE(accel, max_accel_steps_per_s2); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 05c5c44cee..8c1810c3a8 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -317,7 +317,7 @@ class Planner { static float junction_deviation_mm; // (mm) M205 J #if ENABLED(LIN_ADVANCE) static float max_e_jerk // Calculated from junction_deviation_mm - TERN_(DISTINCT_E_FACTORS, [EXTRUDERS]); + [TERN(DISTINCT_E_FACTORS, EXTRUDERS, 1)]; #endif #endif @@ -840,13 +840,9 @@ class Planner { #if HAS_LINEAR_E_JERK FORCE_INLINE static void recalculate_max_e_jerk() { - #define GET_MAX_E_JERK(N) SQRT(junction_deviation_mm * (N) * SQRT(0.5) / (1.0f - SQRT(0.5))) - #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, EXTRUDERS) - max_e_jerk[i] = GET_MAX_E_JERK(settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]); - #else - max_e_jerk = GET_MAX_E_JERK(settings.max_acceleration_mm_per_s2[E_AXIS]); - #endif + const float prop = junction_deviation_mm * SQRT(0.5) / (1.0f - SQRT(0.5)); + LOOP_L_N(i, EXTRUDERS) + max_e_jerk[E_AXIS_N(i)] = SQRT(prop * settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]); } #endif From 39263efef742ba8d42e3a93f63fe19bfbc5ce7c3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 May 2020 23:46:24 -0500 Subject: [PATCH 0395/1454] Allow more serial parameters --- Marlin/src/core/serial.h | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 7050caa1f0..dcae748057 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -185,6 +185,12 @@ extern uint8_t marlin_debug_flags; #define _SELP_22(a,b,V...) do{ _SEP_2(a,b); _SELP_20(V); }while(0) #define _SELP_23(a,b,V...) do{ _SEP_2(a,b); _SELP_21(V); }while(0) #define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0) // Eat two args, pass the rest up +#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(1) // Eat two args, pass the rest up +#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(2) // Eat two args, pass the rest up +#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(3) // Eat two args, pass the rest up +#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(4) // Eat two args, pass the rest up +#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(5) // Eat two args, pass the rest up +#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(6) // Eat two args, pass the rest up #define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) @@ -215,6 +221,12 @@ extern uint8_t marlin_debug_flags; #define _SELP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_20_P(V); }while(0) #define _SELP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_21_P(V); }while(0) #define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0) // Eat two args, pass the rest up +#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(1) // Eat two args, pass the rest up +#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(2) // Eat two args, pass the rest up +#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(3) // Eat two args, pass the rest up +#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(4) // Eat two args, pass the rest up +#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(5) // Eat two args, pass the rest up +#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(6) // Eat two args, pass the rest up #define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V) From eeabe66fc49501222fc458f5c298893e4d88ee17 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 00:28:39 -0500 Subject: [PATCH 0396/1454] Some distinct E helpers --- Marlin/src/inc/Conditionals_LCD.h | 5 ++++- .../screens/max_acceleration_screen.cpp | 14 +++++++------- .../screens/max_velocity_screen.cpp | 8 +++++--- Marlin/src/module/planner.cpp | 17 +++++------------ Marlin/src/module/planner.h | 7 +++---- Marlin/src/module/stepper/trinamic.cpp | 2 +- 6 files changed, 25 insertions(+), 28 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index e6c671f713..3ea27be420 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -408,7 +408,6 @@ #if EXTRUDERS == 0 #undef EXTRUDERS #define EXTRUDERS 0 - #undef DISTINCT_E_FACTORS #undef SINGLENOZZLE #undef SWITCHING_EXTRUDER #undef SWITCHING_NOZZLE @@ -513,12 +512,16 @@ * DISTINCT_E_FACTORS affects how some E factors are accessed */ #if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 + #define DISTINCT_E E_STEPPERS #define XYZE_N (XYZ + E_STEPPERS) + #define E_INDEX_N(E) (E) #define E_AXIS_N(E) AxisEnum(E_AXIS + E) #define UNUSED_E(E) NOOP #else #undef DISTINCT_E_FACTORS + #define DISTINCT_E 1 #define XYZE_N XYZE + #define E_INDEX_N(E) 0 #define E_AXIS_N(E) E_AXIS #define UNUSED_E(E) UNUSED(E) #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp index 8f7af4b81e..305fd0fc35 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp @@ -38,16 +38,16 @@ void MaxAccelerationScreen::onRedraw(draw_mode_t what) { w.color(x_axis) .adjuster( 2, GET_TEXT_F(MSG_AMAX_X), getAxisMaxAcceleration_mm_s2(X) ); w.color(y_axis) .adjuster( 4, GET_TEXT_F(MSG_AMAX_Y), getAxisMaxAcceleration_mm_s2(Y) ); w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_AMAX_Z), getAxisMaxAcceleration_mm_s2(Z) ); - #if EXTRUDERS == 1 || DISABLED(DISTINCT_E_FACTORS) + #if DISTINCT_E == 1 w.color(e_axis).adjuster( 8, GET_TEXT_F(MSG_AMAX_E), getAxisMaxAcceleration_mm_s2(E0) ); - #elif EXTRUDERS > 1 + #elif DISTINCT_E > 1 w.heading(GET_TEXT_F(MSG_AMAX_E)); w.color(e_axis).adjuster( 8, F(LCD_STR_E0), getAxisMaxAcceleration_mm_s2(E0) ); w.color(e_axis).adjuster(10, F(LCD_STR_E1), getAxisMaxAcceleration_mm_s2(E1) ); - #if EXTRUDERS > 2 + #if DISTINCT_E > 2 w.color(e_axis).adjuster(12, F(LCD_STR_E2), getAxisMaxAcceleration_mm_s2(E2) ); #endif - #if EXTRUDERS > 3 + #if DISTINCT_E > 3 w.color(e_axis).adjuster(14, F(LCD_STR_E3), getAxisMaxAcceleration_mm_s2(E3) ); #endif #endif @@ -65,15 +65,15 @@ bool MaxAccelerationScreen::onTouchHeld(uint8_t tag) { case 7: UI_INCREMENT(AxisMaxAcceleration_mm_s2, Z ); break; case 8: UI_DECREMENT(AxisMaxAcceleration_mm_s2, E0); break; case 9: UI_INCREMENT(AxisMaxAcceleration_mm_s2, E0); break; - #if EXTRUDERS > 1 && ENABLED(DISTINCT_E_FACTORS) + #if DISTINCT_E > 1 case 10: UI_DECREMENT(AxisMaxAcceleration_mm_s2, E1); break; case 11: UI_INCREMENT(AxisMaxAcceleration_mm_s2, E1); break; #endif - #if EXTRUDERS > 2 && ENABLED(DISTINCT_E_FACTORS) + #if DISTINCT_E > 2 case 12: UI_DECREMENT(AxisMaxAcceleration_mm_s2, E2); break; case 13: UI_INCREMENT(AxisMaxAcceleration_mm_s2, E2); break; #endif - #if EXTRUDERS > 3 && ENABLED(DISTINCT_E_FACTORS) + #if DISTINCT_E > 3 case 14: UI_DECREMENT(AxisMaxAcceleration_mm_s2, E3); break; case 15: UI_INCREMENT(AxisMaxAcceleration_mm_s2, E3); break; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp index 864f6b735d..ebe0171246 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp @@ -64,17 +64,19 @@ bool MaxVelocityScreen::onTouchHeld(uint8_t tag) { case 5: UI_INCREMENT(AxisMaxFeedrate_mm_s, Y); break; case 6: UI_DECREMENT(AxisMaxFeedrate_mm_s, Z); break; case 7: UI_INCREMENT(AxisMaxFeedrate_mm_s, Z); break; + #if DISTINCT_E > 0 case 8: UI_DECREMENT(AxisMaxFeedrate_mm_s, E0); break; case 9: UI_INCREMENT(AxisMaxFeedrate_mm_s, E0); break; - #if EXTRUDERS > 1 && ENABLED(DISTINCT_E_FACTORS) + #endif + #if DISTINCT_E > 1 case 10: UI_DECREMENT(AxisMaxFeedrate_mm_s, E1); break; case 11: UI_INCREMENT(AxisMaxFeedrate_mm_s, E1); break; #endif - #if EXTRUDERS > 2 && ENABLED(DISTINCT_E_FACTORS) + #if DISTINCT_E > 2 case 12: UI_DECREMENT(AxisMaxFeedrate_mm_s, E2); break; case 13: UI_INCREMENT(AxisMaxFeedrate_mm_s, E2); break; #endif - #if EXTRUDERS > 3 && ENABLED(DISTINCT_E_FACTORS) + #if DISTINCT_E > 3 case 14: UI_DECREMENT(AxisMaxFeedrate_mm_s, E3); break; case 15: UI_INCREMENT(AxisMaxFeedrate_mm_s, E3); break; #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 2d68022c10..aec1e48402 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -134,9 +134,8 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step #if HAS_JUNCTION_DEVIATION float Planner::junction_deviation_mm; // (mm) M205 J - #if ENABLED(LIN_ADVANCE) - float Planner::max_e_jerk // Calculated from junction_deviation_mm - [TERN(DISTINCT_E_FACTORS, EXTRUDERS, 1)]; + #if HAS_LINEAR_E_JERK + float Planner::max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm #endif #endif @@ -2139,7 +2138,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(LIN_ADVANCE) - #define MAX_E_JERK(N) TERN(HAS_JUNCTION_DEVIATION, max_e_jerk[E_AXIS_N(N)], max_jerk.e) + #define MAX_E_JERK(N) TERN(HAS_LINEAR_E_JERK, max_e_jerk[E_INDEX_N(N)], max_jerk.e) /** * @@ -2179,24 +2178,18 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } #endif - #if ENABLED(DISTINCT_E_FACTORS) - #define ACCEL_IDX extruder - #else - #define ACCEL_IDX 0 - #endif - // Limit acceleration per axis if (block->step_event_count <= cutoff_long) { LIMIT_ACCEL_LONG(A_AXIS, 0); LIMIT_ACCEL_LONG(B_AXIS, 0); LIMIT_ACCEL_LONG(C_AXIS, 0); - LIMIT_ACCEL_LONG(E_AXIS, ACCEL_IDX); + LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)); } else { LIMIT_ACCEL_FLOAT(A_AXIS, 0); LIMIT_ACCEL_FLOAT(B_AXIS, 0); LIMIT_ACCEL_FLOAT(C_AXIS, 0); - LIMIT_ACCEL_FLOAT(E_AXIS, ACCEL_IDX); + LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)); } } block->acceleration_steps_per_s2 = accel; diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 8c1810c3a8..9e5088f55a 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -315,9 +315,8 @@ class Planner { #if HAS_JUNCTION_DEVIATION static float junction_deviation_mm; // (mm) M205 J - #if ENABLED(LIN_ADVANCE) - static float max_e_jerk // Calculated from junction_deviation_mm - [TERN(DISTINCT_E_FACTORS, EXTRUDERS, 1)]; + #if HAS_LINEAR_E_JERK + static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm #endif #endif @@ -842,7 +841,7 @@ class Planner { FORCE_INLINE static void recalculate_max_e_jerk() { const float prop = junction_deviation_mm * SQRT(0.5) / (1.0f - SQRT(0.5)); LOOP_L_N(i, EXTRUDERS) - max_e_jerk[E_AXIS_N(i)] = SQRT(prop * settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]); + max_e_jerk[E_INDEX_N(i)] = SQRT(prop * settings.max_acceleration_mm_per_s2[E_INDEX_N(i)]); } #endif diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 48a4ff85e9..e2bf706bf1 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -58,7 +58,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) #define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS) -#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 +#if DISTINCT_E > 1 #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI) #define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI) #else From d2b7671253d593d4b6207653a80ea064043ff4f0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 00:59:22 -0500 Subject: [PATCH 0397/1454] No Z stall by default --- Marlin/Configuration_adv.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 3d66ce72ff..6fca978d5c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2395,10 +2395,10 @@ #define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY #define Y_STALL_SENSITIVITY 8 #define Y2_STALL_SENSITIVITY Y_STALL_SENSITIVITY - #define Z_STALL_SENSITIVITY 8 - #define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY - #define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY - #define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define Z_STALL_SENSITIVITY 8 + //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define SPI_ENDSTOPS // TMC2130 only //#define IMPROVE_HOMING_RELIABILITY #endif From ac5249a76c1d277275fb6ede8e4ca6ed406aa264 Mon Sep 17 00:00:00 2001 From: Axel Date: Tue, 5 May 2020 02:07:02 -0400 Subject: [PATCH 0398/1454] Update README MCU/boards (#17827) --- README.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/README.md b/README.md index 6011d5e243..33181bb659 100644 --- a/README.md +++ b/README.md @@ -69,6 +69,12 @@ Marlin 2.0 introduces a layer of abstraction so that all the existing high-level boards|processor|speed|flash|sram|logic|fpu ----|---------|-----|-----|----|-----|--- [Arduino STM32](https://github.com/rogerclarkmelbourne/Arduino_STM32)|[STM32F1](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html) ARM-Cortex M3|72MHz|256-512k|48-64k|3.3V|no + [Geeetech3D GTM32](https://github.com/Geeetech3D/Diagram/blob/master/Rostock301/Hardware_GTM32_PRO_VB.pdf)|[STM32F1](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html) ARM-Cortex M3|72MHz|256-512k|48-64k|3.3V|no + + #### STM32F4 + + boards|processor|speed|flash|sram|logic|fpu + ----|---------|-----|-----|----|-----|--- [STEVAL-3DP001V1](http://www.st.com/en/evaluation-tools/steval-3dp001v1.html)|[STM32F401VE Arm-Cortex M4](http://www.st.com/en/microcontrollers/stm32f401ve.html)|84MHz|512k|64+32k|3.3-5V|yes #### Teensy++ 2.0 From 973a6990b53afd922006f73dc7c7d26bd027f85f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 01:24:20 -0500 Subject: [PATCH 0399/1454] Trailing whitespace --- Marlin/src/module/thermistor/thermistors.h | 2 +- README.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index b66e30b5cc..106adef6cc 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -110,7 +110,7 @@ #include "thermistor_21.h" #endif #if ANY_THERMISTOR_IS(22) // Thermistor in a Rostock 301 hot end, calibrated with a multimeter - #include "thermistor_22.h" + #include "thermistor_22.h" #endif #if ANY_THERMISTOR_IS(23) // By AluOne #12622. Formerly 22 above. May need calibration/checking. #include "thermistor_23.h" diff --git a/README.md b/README.md index 33181bb659..187e11150d 100644 --- a/README.md +++ b/README.md @@ -70,7 +70,7 @@ Marlin 2.0 introduces a layer of abstraction so that all the existing high-level ----|---------|-----|-----|----|-----|--- [Arduino STM32](https://github.com/rogerclarkmelbourne/Arduino_STM32)|[STM32F1](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html) ARM-Cortex M3|72MHz|256-512k|48-64k|3.3V|no [Geeetech3D GTM32](https://github.com/Geeetech3D/Diagram/blob/master/Rostock301/Hardware_GTM32_PRO_VB.pdf)|[STM32F1](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html) ARM-Cortex M3|72MHz|256-512k|48-64k|3.3V|no - + #### STM32F4 boards|processor|speed|flash|sram|logic|fpu From 2acdd2fadc0fda6e53ea70957273c7c0f1c931a3 Mon Sep 17 00:00:00 2001 From: Axel Date: Tue, 5 May 2020 03:25:22 -0400 Subject: [PATCH 0400/1454] Add Mightyboard Mega env (#17861) --- platformio.ini | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/platformio.ini b/platformio.ini index 9f77af1afc..a2c587ebc9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -75,6 +75,28 @@ lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip src_filter = ${common.default_src_filter} + +# +# MightyBoard ATmega2560 (MegaCore 100 pin boards variants) +# +[env:MightyBoard1280] +platform = atmelavr +board = ATmega1280 +board_build.f_cpu = 16000000L +lib_deps = ${common.lib_deps} + TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip +src_filter = ${common.default_src_filter} + + +# +# MightyBoard ATmega2560 (MegaCore 100 pin boards variants) +# +[env:MightyBoard2560] +platform = atmelavr +board = ATmega2560 +board_build.f_cpu = 16000000L +lib_deps = ${common.lib_deps} + TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip +src_filter = ${common.default_src_filter} + + # # RAMBo # From 3fd8ef52c5d4a51a25207ba2e3d67a783cbdea88 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Tue, 5 May 2020 09:38:06 +0200 Subject: [PATCH 0401/1454] More FTDI EVE fixes (RAMPS, Cheetah) (#17759) --- Marlin/Configuration_adv.h | 2 +- .../lib/ftdi_eve_touch_ui/pin_mappings.h | 51 ++++++++--------- Marlin/src/pins/ramps/pins_RAMPS.h | 2 + Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 56 +++++++++++++++---- 4 files changed, 72 insertions(+), 39 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6fca978d5c..8d6e67582d 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1387,7 +1387,7 @@ //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping //#define CHEETAH_TFT_PINMAP // FYSETC Cheetah pin mapping - //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, FYSETC Cheetah and Stock boards) EXP1 pin mapping + //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, and Stock boards) EXP1 pin mapping //#define GENERIC_EXP2_PINMAP // GENERIC EXP2 pin mapping //#define OTHER_PIN_LAYOUT // Define pins manually below diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 2187ebd8ee..3b9dc56bc1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -27,31 +27,13 @@ * without adding new pin definitions to the board. */ -#ifdef CHEETAH_TFT_PINMAP - #ifndef __MARLIN_FIRMWARE__ - #error "This pin mapping requires Marlin." - #endif - - #define CLCD_SPI_BUS 2 - - #define CLCD_MOD_RESET PC9 - #define CLCD_SPI_CS PB12 - - //#define CLCD_USE_SOFT_SPI - #if ENABLED(CLCD_USE_SOFT_SPI) - #define CLCD_SOFT_SPI_MOSI PB15 - #define CLCD_SOFT_SPI_MISO PB14 - #define CLCD_SOFT_SPI_SCLK PB13 - #endif -#endif - #ifdef S6_TFT_PINMAP #ifndef __MARLIN_FIRMWARE__ #error "This pin mapping requires Marlin." #endif - #define CLCD_SPI_CS PC7 - #define CLCD_MOD_RESET PC6 + #define CLCD_SPI_CS PC7 + #define CLCD_MOD_RESET PC6 #endif #ifdef CR10_TFT_PINMAP @@ -60,13 +42,13 @@ #endif #define CLCD_USE_SOFT_SPI - #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 // PORTA1 Pin 6 - #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE // PORTC1 Pin 8 - #define CLCD_SPI_CS LCD_PINS_RS // PORTA3 Pin 7 - #define CLCD_SOFT_SPI_MISO 16 // PORTC0 BTN_ENC Pin 2 - #define CLCD_MOD_RESET 11 // PORTD3 BTN_EN1 Pin 3 - #define CLCD_AUX_0 10 // PORTD2 BTN_EN2 Pin 5 - #define CLCD_AUX_1 BEEPER_PIN // PORTA4 Pin 1 + #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 // PORTA1 Pin 6 + #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE // PORTC1 Pin 8 + #define CLCD_SPI_CS LCD_PINS_RS // PORTA3 Pin 7 + #define CLCD_SOFT_SPI_MISO 16 // PORTC0 BTN_ENC Pin 2 + #define CLCD_MOD_RESET 11 // PORTD3 BTN_EN1 Pin 3 + #define CLCD_AUX_0 10 // PORTD2 BTN_EN2 Pin 5 + #define CLCD_AUX_1 BEEPER_PIN // PORTA4 Pin 1 #endif /** @@ -181,3 +163,18 @@ #define CLCD_MOD_RESET BTN_EN1 #define CLCD_SPI_CS LCD_PINS_RS #endif + +#ifdef CHEETAH_TFT_PINMAP + #ifndef __MARLIN_FIRMWARE__ + #error "This pin mapping requires Marlin." + #endif + + #define CLCD_MOD_RESET BTN_EN2 + #define CLCD_SPI_CS LCD_PINS_RS + + #if ENABLED(CLCD_USE_SOFT_SPI) + #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE + #define CLCD_SOFT_SPI_MISO LCD_PINS_RS + #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 + #endif +#endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index c27b766688..4ba2628b09 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -753,6 +753,8 @@ * EXP2-1 ----------- EXP1-2 * EXP1-10 ----------- EXP1-1 * + * NOTE: The MISO pin should not get a 5V signal. + * To fix, insert a 1N4148 diode in the MISO line. */ #define BEEPER_PIN 37 diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 63377f8e16..140e1acfb4 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -107,15 +107,35 @@ // // LCD Pins // +/** + * _____ + * 5V | 1 2 | GND + * (MOSI) PB15 | 3 4 | PB12 (LCD_EN) + * (SCK) PB13 | 5 6 PC11 (BTN_EN1) + * (LCD_RS) PB14 | 7 8 | PC10 (BTN_EN2) + * (BTN_ENC) PC12 | 9 10| PC9 (BEEPER) + * ----- + * EXP1 + */ + +#define EXPA1_03_PIN PB15 +#define EXPA1_04_PIN PB12 +#define EXPA1_05_PIN PB13 +#define EXPA1_06_PIN PC11 +#define EXPA1_07_PIN PB14 +#define EXPA1_08_PIN PC10 +#define EXPA1_09_PIN PC12 +#define EXPA1_10_PIN PC9 + #if HAS_SPI_LCD - #define BEEPER_PIN PC9 + #define BEEPER_PIN EXPA1_10_PIN #if HAS_GRAPHICAL_LCD - #define DOGLCD_A0 PB14 - #define DOGLCD_CS PB12 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define DOGLCD_A0 EXPA1_07_PIN + #define DOGLCD_CS EXPA1_04_PIN + #define DOGLCD_SCK EXPA1_05_PIN + #define DOGLCD_MOSI EXPA1_03_PIN //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 @@ -125,9 +145,9 @@ #endif #endif - #define LCD_PINS_RS PB12 // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 PB13 // SCLK - #define LCD_PINS_ENABLE PB15 // DATA MOSI + #define LCD_PINS_RS EXPA1_04_PIN // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 EXPA1_05_PIN // SCLK + #define LCD_PINS_ENABLE EXPA1_03_PIN // DATA MOSI // not connected to a pin #define SD_DETECT_PIN PC3 @@ -145,9 +165,23 @@ //#define LCD_CONTRAST_INIT 190 #if ENABLED(NEWPANEL) - #define BTN_EN1 PC11 - #define BTN_EN2 PC10 - #define BTN_ENC PC12 + #define BTN_EN1 EXPA1_06_PIN + #define BTN_EN2 EXPA1_08_PIN + #define BTN_ENC EXPA1_09_PIN #endif #endif + +#if ENABLED(TOUCH_UI_FTDI_EVE) + #define BEEPER_PIN EXPA1_10_PIN + + #define BTN_EN2 EXPA1_08_PIN + + #define CLCD_SPI_BUS 2 + //#define CLCD_USE_SOFT_SPI + #if ENABLED(CLCD_USE_SOFT_SPI) + #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_D4 EXPA1_07_PIN + #define LCD_PINS_ENABLE EXPA1_05_PIN + #endif +#endif From 852a8d6685ec1137eb65e78fa748cae41fbd36b6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 03:31:03 -0500 Subject: [PATCH 0402/1454] Configurable kill pin state Co-Authored-By: AbdullahGheith --- Marlin/src/MarlinCore.cpp | 12 ++++++++---- Marlin/src/MarlinCore.h | 7 +++++++ Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 3 ++- 3 files changed, 17 insertions(+), 5 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 26a7fb0684..994d0f7ec8 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -245,7 +245,11 @@ millis_t max_inactive_time, // = 0 void setup_killpin() { #if HAS_KILL - SET_INPUT_PULLUP(KILL_PIN); + #if KILL_PIN_STATE + SET_INPUT_PULLDOWN(KILL_PIN); + #else + SET_INPUT_PULLUP(KILL_PIN); + #endif #endif } @@ -496,7 +500,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { // ------------------------------------------------------------------------------- static int killCount = 0; // make the inactivity button a bit less responsive const int KILL_DELAY = 750; - if (!READ(KILL_PIN)) + if (kill_state()) killCount++; else if (killCount > 0) killCount--; @@ -770,10 +774,10 @@ void minkill(const bool steppers_off/*=false*/) { #if HAS_KILL // Wait for kill to be released - while (!READ(KILL_PIN)) watchdog_refresh(); + while (kill_state()) watchdog_refresh(); // Wait for kill to be pressed - while (READ(KILL_PIN)) watchdog_refresh(); + while (!kill_state()) watchdog_refresh(); void (*resetFunc)() = 0; // Declare resetFunc() at address 0 resetFunc(); // Jump to address 0 diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 7f6d4432db..1ed8974835 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -110,6 +110,13 @@ void protected_pin_err(); inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); } #endif +#if HAS_KILL + #ifndef KILL_PIN_STATE + #define KILL_PIN_STATE LOW + #endif + inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; } +#endif + #if ENABLED(G29_RETRY_AND_RECOVER) void event_probe_recover(); void event_probe_failure(); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 7d991fcccd..8385c4bdf9 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1683,8 +1683,9 @@ SERIAL_EOL(); #if HAS_KILL - SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), " state:", READ(KILL_PIN)); + SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), " state:", int(kill_state())); #endif + SERIAL_EOL(); serial_delay(50); From 7a2cc782b406f7e89a0a61d168cc7a5d90835c06 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 03:09:40 -0500 Subject: [PATCH 0403/1454] Clean up planner modifier methods --- Marlin/src/module/motion.cpp | 12 ++---------- Marlin/src/module/planner.cpp | 6 +----- Marlin/src/module/planner.h | 19 +++++++------------ 3 files changed, 10 insertions(+), 27 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 27e3fa125d..021405b4a9 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -221,11 +221,7 @@ void report_real_position() { npos.e = planner.get_axis_position_mm(E_AXIS); #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(npos - #if HAS_LEVELING - , true - #endif - ); + planner.unapply_modifiers(npos, true); #endif report_logical_position(npos); @@ -304,11 +300,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { pos.e = planner.get_axis_position_mm(E_AXIS); #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(pos - #if HAS_LEVELING - , true - #endif - ); + planner.unapply_modifiers(pos, true); #endif if (axis == ALL_AXES) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index aec1e48402..9c1071c6fb 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2742,11 +2742,7 @@ void Planner::set_machine_position_mm(const float &a, const float &b, const floa void Planner::set_position_mm(const float &rx, const float &ry, const float &rz, const float &e) { xyze_pos_t machine = { rx, ry, rz, e }; #if HAS_POSITION_MODIFIERS - apply_modifiers(machine - #if HAS_LEVELING - , true - #endif - ); + apply_modifiers(machine, true); #endif #if IS_KINEMATIC position_cart.set(rx, ry, rz, e); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 9e5088f55a..f2b90cd994 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -547,6 +547,9 @@ class Planner { unapply_leveling(raw); leveling_active = false; } + #else + FORCE_INLINE static void apply_leveling(xyz_pos_t&) {} + FORCE_INLINE static void unapply_leveling(xyz_pos_t&) {} #endif #if ENABLED(FWRETRACT) @@ -557,23 +560,15 @@ class Planner { #endif #if HAS_POSITION_MODIFIERS - FORCE_INLINE static void apply_modifiers(xyze_pos_t &pos - #if HAS_LEVELING - , bool leveling = ENABLED(PLANNER_LEVELING) - #endif - ) { + FORCE_INLINE static void apply_modifiers(xyze_pos_t &pos, bool leveling=ENABLED(PLANNER_LEVELING)) { TERN_(SKEW_CORRECTION, skew(pos)); - TERN_(HAS_LEVELING, if (leveling) apply_leveling(pos)); + if (leveling) apply_leveling(pos); TERN_(FWRETRACT, apply_retract(pos)); } - FORCE_INLINE static void unapply_modifiers(xyze_pos_t &pos - #if HAS_LEVELING - , bool leveling = ENABLED(PLANNER_LEVELING) - #endif - ) { + FORCE_INLINE static void unapply_modifiers(xyze_pos_t &pos, bool leveling=ENABLED(PLANNER_LEVELING)) { TERN_(FWRETRACT, unapply_retract(pos)); - TERN_(HAS_LEVELING, if (leveling) unapply_leveling(pos)); + if (leveling) unapply_leveling(pos); TERN_(SKEW_CORRECTION, unskew(pos)); } #endif // HAS_POSITION_MODIFIERS From 39f703310b8da3b95ad08c3eecd642d76e88fd78 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 17:55:35 -0500 Subject: [PATCH 0404/1454] Move S_FMT to HAL, apply to mixer --- Marlin/src/HAL/AVR/HAL.h | 6 ++---- Marlin/src/HAL/HAL.h | 5 +++++ Marlin/src/core/macros.h | 7 ------- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 8 ++++---- 4 files changed, 11 insertions(+), 15 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index f715295d0a..f319868e36 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -50,7 +50,8 @@ // Defines // ------------------------ -//#define analogInputToDigitalPin(IO) IO +// AVR PROGMEM extension for sprintf_P +#define S_FMT "%S" #ifndef CRITICAL_SECTION_START #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() @@ -60,9 +61,6 @@ #define ENABLE_ISRS() sei() #define DISABLE_ISRS() cli() -// On AVR this is in math.h? -//#define square(x) ((x)*(x)) - // ------------------------ // Types // ------------------------ diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index 614c6cbaf9..b38f9567bd 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -31,6 +31,11 @@ #define I2C_ADDRESS(A) (A) #endif +// Needed for AVR sprintf_P PROGMEM extension +#ifndef S_FMT + #define S_FMT "%s" +#endif + inline void watchdog_refresh() { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); } diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 88a807c570..edab6ae5bc 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -76,13 +76,6 @@ // Nanoseconds per cycle #define NANOSECONDS_PER_CYCLE (1000000000.0 / F_CPU) -// Macros to make sprintf_P read from PROGMEM (AVR extension) -#ifdef __AVR__ - #define S_FMT "%S" -#else - #define S_FMT "%s" -#endif - // Macros to make a string from a macro #define STRINGIFY_(M) #M #define STRINGIFY(M) STRINGIFY_(M) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 5fea16bf97..8c67ff10ab 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -695,19 +695,19 @@ void MarlinUI::draw_status_screen() { // Two-component mix / gradient instead of XY char mixer_messages[12]; - const char *mix_label; + PGM_P mix_label; #if ENABLED(GRADIENT_MIX) if (mixer.gradient.enabled) { mixer.update_mix_from_gradient(); - mix_label = "Gr"; + mix_label = PSTR("Gr"); } else #endif { mixer.update_mix_from_vtool(); - mix_label = "Mx"; + mix_label = PSTR("Mx"); } - sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + sprintf_P(mixer_messages, PSTR(S_FMT " %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(X_LABEL_POS, XYZ_BASELINE, mixer_messages); #else From 9df7992de8a6b6d5794c837c8cb51f9aa01f7a7c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 6 May 2020 00:03:27 +0000 Subject: [PATCH 0405/1454] [cron] Bump distribution date (2020-05-06) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e401b45b69..248b50c5e3 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-05" + #define STRING_DISTRIBUTION_DATE "2020-05-06" #endif /** From 7a03c5a0c6edb26bfea66e70433d4fa158d4687d Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Wed, 6 May 2020 02:20:02 +0200 Subject: [PATCH 0406/1454] Update Italian language (#17888) --- Marlin/src/lcd/language/language_it.h | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 2b903d80a1..f7dce0709d 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -262,8 +262,12 @@ namespace Language_it { PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autotemp"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("On"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Off"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Calibrazione PID"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Calibraz. PID *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Calibr.PID eseguita"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita. Estrusore errato."); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita. Temperatura troppo alta."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto."); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); @@ -299,6 +303,8 @@ namespace Language_it { PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Ritrazione"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Spostamento"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passi/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("passi/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("passi/mm"); From 9ce950e3c1cb0c15a27a20db3f3f02f3c8ddca17 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 May 2020 20:15:37 -0500 Subject: [PATCH 0407/1454] Move M114 options down --- Marlin/Configuration_adv.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 8d6e67582d..453c47753e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -286,11 +286,6 @@ #endif #endif -// Extra options for the M114 "Current Position" report -//#define M114_DETAIL // Use 'M114` for details to check planner calculations -//#define M114_REALTIME // Real current position based on forward kinematics -//#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed. - // Show Temperature ADC value // Enable for M105 to include ADC values read from temperature sensors. //#define SHOW_TEMP_ADC_VALUES @@ -2959,6 +2954,11 @@ */ //#define NO_WORKSPACE_OFFSETS +// Extra options for the M114 "Current Position" report +//#define M114_DETAIL // Use 'M114` for details to check planner calculations +//#define M114_REALTIME // Real current position based on forward kinematics +//#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed. + /** * Set the number of proportional font spaces required to fill up a typical character space. * This can help to better align the output of commands like `G29 O` Mesh Output. From a4c981469e317b30ff21fba109e1b126e5dcafcf Mon Sep 17 00:00:00 2001 From: Gurmeet Athwal Date: Wed, 6 May 2020 10:04:04 +0530 Subject: [PATCH 0408/1454] Extended reporting options (#16741) --- Marlin/Configuration_adv.h | 5 + Marlin/src/HAL/AVR/HAL.h | 3 + Marlin/src/HAL/HAL.h | 5 + Marlin/src/MarlinCore.cpp | 31 ++--- Marlin/src/core/serial.cpp | 4 +- Marlin/src/feature/host_actions.cpp | 6 +- Marlin/src/gcode/calibrate/G33.cpp | 4 +- Marlin/src/gcode/control/M111.cpp | 23 ++-- Marlin/src/gcode/gcode.cpp | 4 + Marlin/src/gcode/gcode.h | 2 + Marlin/src/gcode/host/M115.cpp | 27 ++++ Marlin/src/gcode/host/M360.cpp | 189 ++++++++++++++++++++++++++++ Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/lcd/ultralcd.cpp | 6 +- buildroot/share/tests/esp32-tests | 2 +- 15 files changed, 268 insertions(+), 45 deletions(-) create mode 100644 Marlin/src/gcode/host/M360.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 453c47753e..25bd339169 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2921,6 +2921,9 @@ * Include capabilities in M115 output */ #define EXTENDED_CAPABILITIES_REPORT +#if ENABLED(EXTENDED_CAPABILITIES_REPORT) + //#define M115_GEOMETRY_REPORT +#endif /** * Expected Printer Check @@ -2979,6 +2982,8 @@ //#define GCODE_CASE_INSENSITIVE // Accept G-code sent to the firmware in lowercase +//#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW + /** * CNC G-code options * Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc. diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index f319868e36..e96193651b 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -53,6 +53,9 @@ // AVR PROGMEM extension for sprintf_P #define S_FMT "%S" +// AVR PROGMEM extension for string define +#define PGMSTR(NAM,STR) const char NAM[] PROGMEM = STR + #ifndef CRITICAL_SECTION_START #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END() SREG = _sreg diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index b38f9567bd..d96692da69 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -36,6 +36,11 @@ #define S_FMT "%s" #endif +// String helper +#ifndef PGMSTR + #define PGMSTR(NAM,STR) constexpr char NAM[] = STR +#endif + inline void watchdog_refresh() { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 994d0f7ec8..73f936bc05 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -183,26 +183,17 @@ #include "libs/L64XX/L64XX_Marlin.h" #endif -const char NUL_STR[] PROGMEM = "", - M112_KILL_STR[] PROGMEM = "M112 Shutdown", - G28_STR[] PROGMEM = "G28", - M21_STR[] PROGMEM = "M21", - M23_STR[] PROGMEM = "M23 %s", - M24_STR[] PROGMEM = "M24", - SP_P_STR[] PROGMEM = " P", - SP_T_STR[] PROGMEM = " T", - SP_X_STR[] PROGMEM = " X", - SP_Y_STR[] PROGMEM = " Y", - SP_Z_STR[] PROGMEM = " Z", - SP_E_STR[] PROGMEM = " E", - X_LBL[] PROGMEM = "X:", - Y_LBL[] PROGMEM = "Y:", - Z_LBL[] PROGMEM = "Z:", - E_LBL[] PROGMEM = "E:", - SP_X_LBL[] PROGMEM = " X:", - SP_Y_LBL[] PROGMEM = " Y:", - SP_Z_LBL[] PROGMEM = " Z:", - SP_E_LBL[] PROGMEM = " E:"; +PGMSTR(NUL_STR, ""); +PGMSTR(M112_KILL_STR, "M112 Shutdown"); +PGMSTR(G28_STR, "G28"); +PGMSTR(M21_STR, "M21"); +PGMSTR(M23_STR, "M23 %s"); +PGMSTR(M24_STR, "M24"); +PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T"); +PGMSTR(X_STR, "X"); PGMSTR(Y_STR, "Y"); PGMSTR(Z_STR, "Z"); PGMSTR(E_STR, "E"); +PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMSTR(E_LBL, "E:"); +PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E"); +PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:"); MarlinState marlin_state = MF_INITIALIZING; diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index bf0df9b3b7..1d3907bc56 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -25,8 +25,8 @@ uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; -static const char errormagic[] PROGMEM = "Error:"; -static const char echomagic[] PROGMEM = "echo:"; +static PGMSTR(errormagic, "Error:"); +static PGMSTR(echomagic, "echo:"); #if NUM_SERIAL > 1 int8_t serial_port_index = 0; diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 96cfc7ed0d..d33ff09498 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -64,8 +64,8 @@ void host_action(const char * const pstr, const bool eol) { #if ENABLED(HOST_PROMPT_SUPPORT) - const char CONTINUE_STR[] PROGMEM = "Continue", - DISMISS_STR[] PROGMEM = "Dismiss"; + PGMSTR(CONTINUE_STR, "Continue"); + PGMSTR(DISMISS_STR, "Dismiss"); #if HAS_RESUME_CONTINUE extern bool wait_for_user; @@ -123,7 +123,7 @@ void host_action(const char * const pstr, const bool eol) { // void host_response_handler(const uint8_t response) { #ifdef DEBUG_HOST_ACTIONS - static const char m876_prefix[] PROGMEM = "M876 Handle Re"; + static PGMSTR(m876_prefix, "M876 Handle Re"); serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("ason: ", host_prompt_reason); serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("sponse: ", response); #endif diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index d7112de506..58afb67402 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -448,7 +448,7 @@ void GcodeSuite::G33() { } // Report settings - PGM_P checkingac = PSTR("Checking... AC"); + PGM_P const checkingac = PSTR("Checking... AC"); serialprintPGM(checkingac); if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)"); SERIAL_EOL(); @@ -624,7 +624,7 @@ void GcodeSuite::G33() { } } else { // dry run - PGM_P enddryrun = PSTR("End DRY-RUN"); + PGM_P const enddryrun = PSTR("End DRY-RUN"); serialprintPGM(enddryrun); SERIAL_ECHO_SP(35); SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3); diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index 20ed44fb2e..d93e1404af 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -28,21 +28,18 @@ void GcodeSuite::M111() { if (parser.seen('S')) marlin_debug_flags = parser.byteval('S'); - static const char str_debug_1[] PROGMEM = STR_DEBUG_ECHO, - str_debug_2[] PROGMEM = STR_DEBUG_INFO, - str_debug_4[] PROGMEM = STR_DEBUG_ERRORS, - str_debug_8[] PROGMEM = STR_DEBUG_DRYRUN, - str_debug_16[] PROGMEM = STR_DEBUG_COMMUNICATION - #if ENABLED(DEBUG_LEVELING_FEATURE) - , str_debug_lvl[] PROGMEM = STR_DEBUG_LEVELING - #endif - ; + static PGMSTR(str_debug_1, STR_DEBUG_ECHO); + static PGMSTR(str_debug_2, STR_DEBUG_INFO); + static PGMSTR(str_debug_4, STR_DEBUG_ERRORS); + static PGMSTR(str_debug_8, STR_DEBUG_DRYRUN); + static PGMSTR(str_debug_16, STR_DEBUG_COMMUNICATION); + #if ENABLED(DEBUG_LEVELING_FEATURE) + static PGMSTR(str_debug_lvl, STR_DEBUG_LEVELING); + #endif static PGM_P const debug_strings[] PROGMEM = { - str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16 - #if ENABLED(DEBUG_LEVELING_FEATURE) - , str_debug_lvl - #endif + str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16, + TERN_(DEBUG_LEVELING_FEATURE, str_debug_lvl) }; SERIAL_ECHO_START(); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index de6fe29e6a..ac5a60ed93 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -663,6 +663,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 305: M305(); break; // M305: Set user thermistor parameters #endif + #if ENABLED(REPETIER_GCODE_M360) + case 360: M360(); break; // M360: Firmware settings + #endif + #if ENABLED(MORGAN_SCARA) case 360: if (M360()) return; break; // M360: SCARA Theta pos1 case 361: if (M361()) return; break; // M361: SCARA Theta pos2 diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 37521e8769..92292f609b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -691,6 +691,8 @@ private: TERN_(HAS_CASE_LIGHT, static void M355()); + TERN_(REPETIER_GCODE_M360, static void M360()); + #if ENABLED(MORGAN_SCARA) static bool M360(); static bool M361(); diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 824c2e166e..6e75388beb 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -23,6 +23,10 @@ #include "../gcode.h" #include "../../inc/MarlinConfig.h" +#if ENABLED(M115_GEOMETRY_REPORT) + #include "../../module/motion.h" +#endif + #if ENABLED(EXTENDED_CAPABILITIES_REPORT) static void cap_line(PGM_P const name, bool ena=false) { SERIAL_ECHOPGM("Cap:"); @@ -117,5 +121,28 @@ void GcodeSuite::M115() { // CHAMBER_TEMPERATURE (M141, M191) cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER)); + // Machine Geometry + #if ENABLED(M115_GEOMETRY_REPORT) + const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, + dmax = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; + xyz_pos_t cmin = dmin, cmax = dmax; + apply_motion_limits(cmin); + apply_motion_limits(cmax); + const xyz_pos_t lmin = dmin.asLogical(), lmax = dmax.asLogical(), + wmin = cmin.asLogical(), wmax = cmax.asLogical(); + SERIAL_ECHOLNPAIR( + "area:{" + "full:{" + "min:{x:", lmin.x, ",y:", lmin.y, ",z:", lmin.z, "}," + "max:{x:", lmax.x, ",y:", lmax.y, ",z:", lmax.z, "}," + "}," + "work:{" + "min:{x:", wmin.x, ",y:", wmin.y, ",z:", wmin.z, "}," + "max:{x:", wmax.x, ",y:", wmax.y, ",z:", wmax.z, "}," + "}" + "}" + ); + #endif + #endif // EXTENDED_CAPABILITIES_REPORT } diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp new file mode 100644 index 0000000000..5c00be30b4 --- /dev/null +++ b/Marlin/src/gcode/host/M360.cpp @@ -0,0 +1,189 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../inc/MarlinConfig.h" + +#if ENABLED(REPETIER_GCODE_M360) + +#include "../gcode.h" + +#include "../../module/motion.h" +#include "../../module/planner.h" + +static void config_prefix(PGM_P const name, PGM_P const pref=nullptr) { + SERIAL_ECHOPGM("Config:"); + if (pref) serialprintPGM(pref); + serialprintPGM(name); + SERIAL_CHAR(':'); +} +static void config_line(PGM_P const name, const float val, PGM_P const pref=nullptr) { + config_prefix(name, pref); + SERIAL_ECHOLN(val); +} + +/** + * M360: Report Firmware configuration + * in RepRapFirmware-compatible format + */ +void GcodeSuite::M360() { + PGMSTR(X_STR, "X"); + PGMSTR(Y_STR, "Y"); + PGMSTR(Z_STR, "Z"); + PGMSTR(JERK_STR, "Jerk"); + + // + // Basics and Enabled items + // + config_line(PSTR("Baudrate"), BAUDRATE); + config_line(PSTR("InputBuffer"), MAX_CMD_SIZE); + config_line(PSTR("PrintlineCache"), BUFSIZE); + config_line(PSTR("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); + config_line(PSTR("SDCard"), ENABLED(SDSUPPORT)); + config_line(PSTR("Fan"), ENABLED(HAS_FAN)); + config_line(PSTR("LCD"), ENABLED(HAS_DISPLAY)); + config_line(PSTR("SoftwarePowerSwitch"), 1); + config_line(PSTR("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE)); + config_line(PSTR("CaseLights"), ENABLED(CASE_LIGHT_ENABLE)); + config_line(PSTR("ZProbe"), ENABLED(HAS_BED_PROBE)); + config_line(PSTR("Autolevel"), ENABLED(HAS_LEVELING)); + config_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS)); + + // + // Homing Directions + // + PGMSTR(H_DIR_STR, "HomeDir"); + config_line(H_DIR_STR, X_HOME_DIR, X_STR); + config_line(H_DIR_STR, Y_HOME_DIR, Y_STR); + config_line(H_DIR_STR, Z_HOME_DIR, Z_STR); + + // + // XYZ Axis Jerk + // + #if HAS_CLASSIC_JERK + if (planner.max_jerk.x == planner.max_jerk.y) + config_line(PSTR("XY"), planner.max_jerk.x, JERK_STR); + else { + config_line(X_STR, planner.max_jerk.x, JERK_STR); + config_line(Y_STR, planner.max_jerk.y, JERK_STR); + } + config_line(Z_STR, planner.max_jerk.z, JERK_STR); + #endif + + // + // Firmware Retraction + // + config_line(PSTR("SupportG10G11"), ENABLED(FWRETRACT)); + #if ENABLED(FWRETRACT) + PGMSTR(RET_STR, "Retraction"); + PGMSTR(UNRET_STR, "RetractionUndo"), + PGMSTR(SPEED_STR, "Speed"); + // M10 Retract with swap (long) moves + config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR); + config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); + config_line(PSTR("ZLift"), fwretract.settings.retract_zraise, RET_STR); + config_line(PSTR("LongLength"), fwretract.settings.swap_retract_length, RET_STR); + // M11 Recover (undo) with swap (long) moves + config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); + config_line(PSTR("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); + config_line(PSTR("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR); + config_line(PSTR("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); + #endif + + // + // Workspace boundaries + // + const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, + dmax = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; + xyz_pos_t cmin = dmin, cmax = dmax; + apply_motion_limits(cmin); + apply_motion_limits(cmax); + const xyz_pos_t lmin = dmin.asLogical(), lmax = dmax.asLogical(), + wmin = cmin.asLogical(), wmax = cmax.asLogical(); + + PGMSTR(MIN_STR, "Min"); + PGMSTR(MAX_STR, "Max"); + PGMSTR(SIZE_STR, "Size"); + config_line(MIN_STR, wmin.x, X_STR); + config_line(MIN_STR, wmin.y, Y_STR); + config_line(MIN_STR, wmin.z, Z_STR); + config_line(MAX_STR, wmax.x, X_STR); + config_line(MAX_STR, wmax.y, Y_STR); + config_line(MAX_STR, wmax.z, Z_STR); + config_line(SIZE_STR, wmax.x - wmin.x, X_STR); + config_line(SIZE_STR, wmax.y - wmin.y, Y_STR); + config_line(SIZE_STR, wmax.z - wmin.z, Z_STR); + + // + // Print and Travel Acceleration + // + #define _ACCEL(A,B) _MIN(planner.settings.max_acceleration_mm_per_s2[A##_AXIS], planner.settings.B) + PGMSTR(P_ACC_STR, "PrintAccel"); + PGMSTR(T_ACC_STR, "TravelAccel"); + config_line(P_ACC_STR, _ACCEL(X, acceleration), X_STR); + config_line(P_ACC_STR, _ACCEL(Y, acceleration), Y_STR); + config_line(P_ACC_STR, _ACCEL(Z, acceleration), Z_STR); + config_line(T_ACC_STR, _ACCEL(X, travel_acceleration), X_STR); + config_line(T_ACC_STR, _ACCEL(Y, travel_acceleration), Y_STR); + config_line(T_ACC_STR, _ACCEL(Z, travel_acceleration), Z_STR); + + config_prefix(PSTR("PrinterType")); + SERIAL_ECHOLNPGM( + TERN_(DELTA, "Delta") + TERN_(IS_SCARA, "SCARA") + TERN_(IS_CORE, "Core") + TERN_(IS_CARTESIAN, "Cartesian") + ); + + // + // Heated Bed + // + config_line(PSTR("HeatedBed"), ENABLED(HAS_HEATED_BED)); + #if HAS_HEATED_BED + config_line(PSTR("MaxBedTemp"), BED_MAX_TARGET); + #endif + + // + // Per-Extruder settings + // + config_line(PSTR("NumExtruder"), EXTRUDERS); + #if EXTRUDERS + #define DIAM_VALUE(N) TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[N]) + #if HAS_LINEAR_E_JERK + #define E_JERK_VAL(N) planner.max_e_jerk[E_INDEX_N(N)] + #elif HAS_CLASSIC_JERK + #define E_JERK_VAL(N) planner.max_jerk.e + #else + #define E_JERK_VAL(N) DEFAULT_EJERK + #endif + #define _EXTR_ITEM(N) do{ \ + PGMSTR(EXTR_STR, "Extr." STRINGIFY(INCREMENT(N)) ":"); \ + config_line(JERK_STR, E_JERK_VAL(N), EXTR_STR); \ + config_line(PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(N)], EXTR_STR); \ + config_line(PSTR("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(N)], EXTR_STR); \ + config_line(PSTR("Diameter"), DIAM_VALUE(N), EXTR_STR); \ + config_line(PSTR("MaxTemp"), (HEATER_##N##_MAXTEMP) - (HOTEND_OVERSHOOT), EXTR_STR); \ + }while(0) + + REPEAT(EXTRUDERS, _EXTR_ITEM); + #endif +} + +#endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 95f630f7ec..12df06c852 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -893,7 +893,7 @@ namespace ExtUI { bool isMachineHomed() { return all_axes_homed(); } PGM_P getFirmwareName_str() { - static const char firmware_name[] PROGMEM = "Marlin " SHORT_BUILD_VERSION; + static PGMSTR(firmware_name, "Marlin " SHORT_BUILD_VERSION); return firmware_name; } diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 73f9cbaa29..deedbb4e14 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1347,13 +1347,13 @@ void MarlinUI::update() { PGM_P printing = GET_TEXT(MSG_PRINTING); PGM_P welcome = GET_TEXT(WELCOME_MSG); #if SERVICE_INTERVAL_1 > 0 - static const char service1[] PROGMEM = { "> " SERVICE_NAME_1 "!" }; + static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); #endif #if SERVICE_INTERVAL_2 > 0 - static const char service2[] PROGMEM = { "> " SERVICE_NAME_2 "!" }; + static PGMSTR(service2, "> " SERVICE_NAME_2 "!"); #endif #if SERVICE_INTERVAL_3 > 0 - static const char service3[] PROGMEM = { "> " SERVICE_NAME_3 "!" }; + static PGMSTR(service3, "> " SERVICE_NAME_3 "!"); #endif PGM_P msg; if (printingIsPaused()) diff --git a/buildroot/share/tests/esp32-tests b/buildroot/share/tests/esp32-tests index 18abab8b06..37a67fcae6 100755 --- a/buildroot/share/tests/esp32-tests +++ b/buildroot/share/tests/esp32-tests @@ -11,7 +11,7 @@ set -e # restore_configs opt_set MOTHERBOARD BOARD_ESPRESSIF_ESP32 -opt_enable WIFISUPPORT GCODE_MACROS BAUD_RATE_GCODE +opt_enable WIFISUPPORT GCODE_MACROS BAUD_RATE_GCODE M115_GEOMETRY_REPORT REPETIER_GCODE_M360 opt_add WIFI_SSID "\"ssid\"" opt_add WIFI_PWD "\"password\"" opt_set TX_BUFFER_SIZE 64 From 544b16639e314af3db5bbe4673089556d7b63ff1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 6 May 2020 01:15:05 -0500 Subject: [PATCH 0409/1454] Fix poll_runout_states bug --- Marlin/src/feature/runout.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 056fc4f5cd..a170d5e323 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -140,6 +140,7 @@ class FilamentSensorBase { #define _INIT_RUNOUT(N) INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN); REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _INIT_RUNOUT) #undef _INIT_RUNOUT + #undef INIT_RUNOUT_PIN } // Return a bitmask of runout pin states @@ -151,10 +152,8 @@ class FilamentSensorBase { // Return a bitmask of runout flag states (1 bits always indicates runout) static inline uint8_t poll_runout_states() { - return poll_runout_pins() ^ uint8_t(TERN0(FIL_RUNOUT_INVERTING, _BV(NUM_RUNOUT_SENSORS) - 1)); + return poll_runout_pins() ^ uint8_t(TERN(FIL_RUNOUT_INVERTING, 0, _BV(NUM_RUNOUT_SENSORS) - 1)); } - - #undef INIT_RUNOUT_PIN }; #if ENABLED(FILAMENT_MOTION_SENSOR) From 0332666d38d494f52f46af575f0bb5cbc3b9546e Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Wed, 6 May 2020 08:16:32 +0200 Subject: [PATCH 0410/1454] Fix Cheetah pins alias (#17882) --- .../src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h | 4 ++-- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 10 ++++++---- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 3b9dc56bc1..7476a1108d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -169,12 +169,12 @@ #error "This pin mapping requires Marlin." #endif - #define CLCD_MOD_RESET BTN_EN2 + #define CLCD_MOD_RESET BTN_EN1 #define CLCD_SPI_CS LCD_PINS_RS #if ENABLED(CLCD_USE_SOFT_SPI) #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE - #define CLCD_SOFT_SPI_MISO LCD_PINS_RS + #define CLCD_SOFT_SPI_MISO LCD_PINS_SCK #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 140e1acfb4..a663061f6c 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -175,13 +175,15 @@ #if ENABLED(TOUCH_UI_FTDI_EVE) #define BEEPER_PIN EXPA1_10_PIN - #define BTN_EN2 EXPA1_08_PIN + #define BTN_EN1 EXPA1_06_PIN + + #define LCD_PINS_RS EXPA1_04_PIN #define CLCD_SPI_BUS 2 //#define CLCD_USE_SOFT_SPI #if ENABLED(CLCD_USE_SOFT_SPI) - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_D4 EXPA1_07_PIN - #define LCD_PINS_ENABLE EXPA1_05_PIN + #define LCD_PINS_ENABLE EXPA1_03_PIN + #define LCD_PINS_SCK EXPA1_07_PIN + #define LCD_PINS_D4 EXPA1_05_PIN #endif #endif From 1aa9d44783f3946f36a49144492b056638dda9f8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 6 May 2020 01:37:50 -0500 Subject: [PATCH 0411/1454] Format some pins --- Marlin/src/pins/samd/pins_RAMPS_144.h | 216 ++++++++++----------- Marlin/src/pins/teensy3/pins_TEENSY31_32.h | 2 +- 2 files changed, 109 insertions(+), 109 deletions(-) diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 082c0412e3..c9cc8c3c67 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -295,55 +295,55 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) // TO TEST - // #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - // #define LCD_PINS_ENABLE 51 // SID (MOSI) - // #define LCD_PINS_D4 52 // SCK (CLK) clock + //#define LCD_PINS_RS 49 // CS chip select /SS chip slave select + //#define LCD_PINS_ENABLE 51 // SID (MOSI) + //#define LCD_PINS_D4 52 // SCK (CLK) clock #elif BOTH(NEWPANEL, PANEL_ONE) // TO TEST - // #define LCD_PINS_RS 40 - // #define LCD_PINS_ENABLE 42 - // #define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 - // #define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 - // #define LCD_PINS_D6 44 - // #define LCD_PINS_D7 56 // Mega/Due:64 - AGCM4:56 + //#define LCD_PINS_RS 40 + //#define LCD_PINS_ENABLE 42 + //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 + //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 + //#define LCD_PINS_D6 44 + //#define LCD_PINS_D7 56 // Mega/Due:64 - AGCM4:56 #else #if ENABLED(CR10_STOCKDISPLAY) // TO TEST - // #define LCD_PINS_RS 27 - // #define LCD_PINS_ENABLE 29 - // #define LCD_PINS_D4 25 + //#define LCD_PINS_RS 27 + //#define LCD_PINS_ENABLE 29 + //#define LCD_PINS_D4 25 #if DISABLED(NEWPANEL) // TO TEST - // #define BEEPER_PIN 37 + //#define BEEPER_PIN 37 #endif #elif ENABLED(ZONESTAR_LCD) // TO TEST - // #define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - // #define LCD_PINS_ENABLE 44 - // #define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 - // #define LCD_PINS_D5 40 - // #define LCD_PINS_D6 42 - // #define LCD_PINS_D7 57 // Mega/Due:65 - AGCM4:57 + //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 + //#define LCD_PINS_ENABLE 44 + //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 + //#define LCD_PINS_D5 40 + //#define LCD_PINS_D6 42 + //#define LCD_PINS_D7 57 // Mega/Due:65 - AGCM4:57 #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST - // #define LCD_PINS_DC 25 // Set as output on init - // #define LCD_PINS_RS 27 // Pull low for 1s to init + //#define LCD_PINS_DC 25 // Set as output on init + //#define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support - // #define DOGLCD_CS 16 - // #define DOGLCD_MOSI 17 - // #define DOGLCD_SCK 23 - // #define DOGLCD_A0 LCD_PINS_DC + //#define DOGLCD_CS 16 + //#define DOGLCD_MOSI 17 + //#define DOGLCD_SCK 23 + //#define DOGLCD_A0 LCD_PINS_DC #else #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 @@ -382,8 +382,8 @@ #if ENABLED(CR10_STOCKDISPLAY) // TO TEST - // #define BTN_EN1 17 - // #define BTN_EN2 23 + //#define BTN_EN1 17 + //#define BTN_EN2 23 #else #define BTN_EN1 31 #define BTN_EN2 33 @@ -397,70 +397,70 @@ #if ENABLED(BQ_LCD_SMART_CONTROLLER) // TO TEST - // #define LCD_BACKLIGHT_PIN 39 + //#define LCD_BACKLIGHT_PIN 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) // TO TEST - // #define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 - // #define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 - // #define BTN_ENC 55 - // #define SD_DETECT_PIN 42 + //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 + //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 + //#define BTN_ENC 55 + //#define SD_DETECT_PIN 42 #elif ENABLED(LCD_I2C_PANELOLU2) // TO TEST - // #define BTN_EN1 47 - // #define BTN_EN2 43 - // #define BTN_ENC 32 - // #define LCD_SDSS SDSS - // #define KILL_PIN 41 + //#define BTN_EN1 47 + //#define BTN_EN2 43 + //#define BTN_ENC 32 + //#define LCD_SDSS SDSS + //#define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) // TO TEST - // #define BTN_EN1 40 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - // #define BTN_EN2 42 - // #define BTN_ENC -1 + //#define BTN_EN1 40 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + //#define BTN_EN2 42 + //#define BTN_ENC -1 - // #define LCD_SDSS SDSS - // #define SD_DETECT_PIN 49 + //#define LCD_SDSS SDSS + //#define SD_DETECT_PIN 49 #elif ANY(VIKI2, miniVIKI) // TO TEST - // #define DOGLCD_CS 45 - // #define DOGLCD_A0 44 - // #define LCD_SCREEN_ROT_180 + //#define DOGLCD_CS 45 + //#define DOGLCD_A0 44 + //#define LCD_SCREEN_ROT_180 - // #define BEEPER_PIN 33 - // #define STAT_LED_RED_PIN 32 - // #define STAT_LED_BLUE_PIN 35 + //#define BEEPER_PIN 33 + //#define STAT_LED_RED_PIN 32 + //#define STAT_LED_BLUE_PIN 35 - // #define BTN_EN1 22 - // #define BTN_EN2 7 - // #define BTN_ENC 39 + //#define BTN_EN1 22 + //#define BTN_EN2 7 + //#define BTN_ENC 39 - // #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - // #define KILL_PIN 31 + //#define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board + //#define KILL_PIN 31 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) // TO TEST - // #define DOGLCD_CS 29 - // #define DOGLCD_A0 27 + //#define DOGLCD_CS 29 + //#define DOGLCD_A0 27 - // #define BEEPER_PIN 23 - // #define LCD_BACKLIGHT_PIN 33 + //#define BEEPER_PIN 23 + //#define LCD_BACKLIGHT_PIN 33 - // #define BTN_EN1 35 - // #define BTN_EN2 37 - // #define BTN_ENC 31 + //#define BTN_EN1 35 + //#define BTN_EN2 37 + //#define BTN_ENC 31 - // #define LCD_SDSS SDSS - // #define SD_DETECT_PIN 49 - // #define KILL_PIN 41 + //#define LCD_SDSS SDSS + //#define SD_DETECT_PIN 49 + //#define KILL_PIN 41 #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) @@ -476,53 +476,53 @@ #if ENABLED(MKS_MINI_12864) // Added in Marlin 1.1.6 // TO TEST - // #define DOGLCD_A0 27 - // #define DOGLCD_CS 25 + //#define DOGLCD_A0 27 + //#define DOGLCD_CS 25 // GLCD features // Uncomment screen orientation - // #define LCD_SCREEN_ROT_90 - // #define LCD_SCREEN_ROT_180 - // #define LCD_SCREEN_ROT_270 + //#define LCD_SCREEN_ROT_90 + //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_270 // not connected to a pin - // #define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) + //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) - // #define BTN_EN1 31 - // #define BTN_EN2 33 + //#define BTN_EN1 31 + //#define BTN_EN2 33 #elif ENABLED(FYSETC_MINI_12864) // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 // TO TEST - // #define DOGLCD_A0 16 - // #define DOGLCD_CS 17 + //#define DOGLCD_A0 16 + //#define DOGLCD_CS 17 - // #define BTN_EN1 33 - // #define BTN_EN2 31 + //#define BTN_EN1 33 + //#define BTN_EN2 31 //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - // #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. + //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST - // #define RGB_LED_R_PIN 25 + //#define RGB_LED_R_PIN 25 #endif #ifndef RGB_LED_G_PIN // TO TEST - // #define RGB_LED_G_PIN 27 + //#define RGB_LED_G_PIN 27 #endif #ifndef RGB_LED_B_PIN // TO TEST - // #define RGB_LED_B_PIN 29 + //#define RGB_LED_B_PIN 29 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) // TO TEST - // #define NEOPIXEL_PIN 25 + //#define NEOPIXEL_PIN 25 #endif #endif @@ -530,30 +530,30 @@ #elif ENABLED(MINIPANEL) // TO TEST - // #define BEEPER_PIN 42 + //#define BEEPER_PIN 42 // not connected to a pin - // #define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) + //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) - // #define DOGLCD_A0 44 - // #define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 + //#define DOGLCD_A0 44 + //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 // GLCD features // Uncomment screen orientation - // #define LCD_SCREEN_ROT_90 - // #define LCD_SCREEN_ROT_180 - // #define LCD_SCREEN_ROT_270 + //#define LCD_SCREEN_ROT_90 + //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_270 - // #define BTN_EN1 40 - // #define BTN_EN2 55 // Mega/Due:63 - AGCM4:55 - // #define BTN_ENC 72 // Mega/Due:59 - AGCM4:72 + //#define BTN_EN1 40 + //#define BTN_EN2 55 // Mega/Due:63 - AGCM4:55 + //#define BTN_ENC 72 // Mega/Due:59 - AGCM4:72 - // #define SD_DETECT_PIN 49 - // #define KILL_PIN 56 // Mega/Due:64 - AGCM4:56 + //#define SD_DETECT_PIN 49 + //#define KILL_PIN 56 // Mega/Due:64 - AGCM4:56 #elif ENABLED(ZONESTAR_LCD) // TO TEST - // #define ADC_KEYPAD_PIN 12 + //#define ADC_KEYPAD_PIN 12 #elif ENABLED(AZSMZ_12864) @@ -562,33 +562,33 @@ #else // Beeper on AUX-4 - // #define BEEPER_PIN 33 + //#define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) // TO TEST - // #define SHIFT_OUT 40 - // #define SHIFT_CLK 44 - // #define SHIFT_LD 42 - // #define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 - // #define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 - // #define BTN_ENC 55 // Mega/Due:63 - AGCM4:55 + //#define SHIFT_OUT 40 + //#define SHIFT_CLK 44 + //#define SHIFT_LD 42 + //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 + //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 + //#define BTN_ENC 55 // Mega/Due:63 - AGCM4:55 #elif ENABLED(PANEL_ONE) // TO TEST - // #define BTN_EN1 72 // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72) - // #define BTN_EN2 55 // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55) - // #define BTN_ENC 49 // AUX3 PIN 7 + //#define BTN_EN1 72 // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72) + //#define BTN_EN2 55 // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55) + //#define BTN_ENC 49 // AUX3 PIN 7 #else // TO TEST - // #define BTN_EN1 37 - // #define BTN_EN2 35 - // #define BTN_ENC 31 + //#define BTN_EN1 37 + //#define BTN_EN2 35 + //#define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) // TO TEST - // #define SD_DETECT_PIN 49 - // #define KILL_PIN 41 + //#define SD_DETECT_PIN 49 + //#define KILL_PIN 41 #endif #endif diff --git a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h index 0f895c9e6b..cdd396bc13 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h @@ -72,7 +72,7 @@ // Heaters / Fans // #define HEATER_0_PIN 20 -// #define HEATER_1_PIN 36 +//#define HEATER_1_PIN 36 #define HEATER_BED_PIN 21 #ifndef FAN_PIN #define FAN_PIN 22 From 7c26a54d3f2434c4d578f58af011a76dd298d4e3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 6 May 2020 03:34:05 -0500 Subject: [PATCH 0412/1454] Fix, clarify LCD_TIMEOUT_TO_STATUS Replaces #17887 Co-Authored-By: Daniel Callander --- .../extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp | 8 ++++---- .../src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h | 2 +- Marlin/src/lcd/ultralcd.cpp | 6 +++--- Marlin/src/lcd/ultralcd.h | 8 ++++++-- 4 files changed, 14 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp index 7e88b7883a..d449876baf 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp @@ -46,7 +46,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #if LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS > 0 if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -66,7 +66,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #if LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS > 0 if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -78,12 +78,12 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #if LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS > 0 last_interaction = millis(); #endif } -#if LCD_TIMEOUT_TO_STATUS +#if LCD_TIMEOUT_TO_STATUS > 0 uint32_t BaseScreen::last_interaction; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index b2d5e55a12..ce77a00b81 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -103,7 +103,7 @@ enum { class BaseScreen : public UIScreen { protected: - #if LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS > 0 static uint32_t last_interaction; #endif diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index deedbb4e14..1193a2fee7 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -121,7 +121,7 @@ MarlinUI ui; #endif #endif -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS +#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 bool MarlinUI::defer_return_to_status; #endif @@ -732,7 +732,7 @@ void MarlinUI::update() { static uint16_t max_display_update_time = 0; millis_t ms = millis(); - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS + #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 static millis_t return_to_status_ms = 0; #define RESET_STATUS_TIMEOUT() (return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS) #else @@ -967,7 +967,7 @@ void MarlinUI::update() { NOLESS(max_display_update_time, millis() - ms); } - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS + #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 // Return to Status Screen after a timeout if (on_status_screen() || defer_return_to_status) RESET_STATUS_TIMEOUT(); diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 33d7de2748..7df6b42e00 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -508,7 +508,11 @@ public: #endif FORCE_INLINE static void defer_status_screen(const bool defer=true) { - TERN(LCD_TIMEOUT_TO_STATUS, defer_return_to_status = defer, UNUSED(defer)); + #if LCD_TIMEOUT_TO_STATUS > 0 + defer_return_to_status = defer; + #else + UNUSED(defer); + #endif } static inline void goto_previous_screen_no_defer() { @@ -612,7 +616,7 @@ private: #if HAS_SPI_LCD #if HAS_LCD_MENU - #if LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS > 0 static bool defer_return_to_status; #else static constexpr bool defer_return_to_status = false; From 6947dc139e4e81fed3986510eb32a93c58bd256c Mon Sep 17 00:00:00 2001 From: Gurmeet Athwal Date: Wed, 6 May 2020 14:10:04 +0530 Subject: [PATCH 0413/1454] Fix M503 output formatting (#17893) --- Marlin/src/module/configuration_store.cpp | 42 +++++++++++------------ 1 file changed, 20 insertions(+), 22 deletions(-) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 25a00224fd..a42aa2d52d 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -3211,6 +3211,7 @@ void MarlinSettings::reset() { #if AXIS_IS_TMC(Z) SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.getMilliamps()); #endif + SERIAL_EOL(); #endif #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) @@ -3225,6 +3226,7 @@ void MarlinSettings::reset() { #if AXIS_IS_TMC(Z2) SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.getMilliamps()); #endif + SERIAL_EOL(); #endif #if AXIS_IS_TMC(Z3) @@ -3278,34 +3280,30 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Hybrid Threshold:"); #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z) say_M913(forReplay); - #endif - #if AXIS_HAS_STEALTHCHOP(X) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); - #endif - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z) + #if AXIS_HAS_STEALTHCHOP(X) + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); + #endif + #if AXIS_HAS_STEALTHCHOP(Y) + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); + #endif + #if AXIS_HAS_STEALTHCHOP(Z) + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); + #endif SERIAL_EOL(); #endif #if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2) say_M913(forReplay); SERIAL_ECHOPGM(" I1"); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2) + #if AXIS_HAS_STEALTHCHOP(X2) + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); + #endif + #if AXIS_HAS_STEALTHCHOP(Y2) + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); + #endif + #if AXIS_HAS_STEALTHCHOP(Z2) + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); + #endif SERIAL_EOL(); #endif From 10e875cd7908d89b50f1cdbbbc34767d31ed2199 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 7 May 2020 00:03:32 +0000 Subject: [PATCH 0414/1454] [cron] Bump distribution date (2020-05-07) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 248b50c5e3..5b3fe05901 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-06" + #define STRING_DISTRIBUTION_DATE "2020-05-07" #endif /** From 6be76af6176676828f69d559d41c02512f0baf74 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 7 May 2020 14:57:25 -0500 Subject: [PATCH 0415/1454] Overrideable CASE_LIGHT_PIN --- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 5 ++++- Marlin/src/pins/mega/pins_MEGACONTROLLER.h | 5 ++++- Marlin/src/pins/mega/pins_MEGATRONICS.h | 5 ++++- Marlin/src/pins/mega/pins_MEGATRONICS_2.h | 5 ++++- Marlin/src/pins/mega/pins_MEGATRONICS_3.h | 5 ++++- Marlin/src/pins/mega/pins_SILVER_GATE.h | 5 ++++- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 5 ++++- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 5 ++++- Marlin/src/pins/rambo/pins_RAMBO.h | 5 ++++- Marlin/src/pins/ramps/pins_3DRAG.h | 4 +++- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 4 +++- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h | 4 +++- Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 4 +++- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 6 +++++- Marlin/src/pins/ramps/pins_MKS_BASE_14.h | 6 +++++- Marlin/src/pins/ramps/pins_RAMPS_OLD.h | 5 ++++- Marlin/src/pins/ramps/pins_RUMBA.h | 5 ++++- Marlin/src/pins/ramps/pins_ULTIMAKER.h | 5 ++++- Marlin/src/pins/sam/pins_ARCHIM2.h | 4 +++- Marlin/src/pins/sanguino/pins_GEN6.h | 5 ++++- Marlin/src/pins/sanguino/pins_GEN7_14.h | 5 ++++- Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h | 5 ++++- Marlin/src/pins/stm32f1/pins_CHITU3D.h | 5 ++++- Marlin/src/pins/teensy2/pins_TEENSY2.h | 5 ++++- Marlin/src/pins/teensy2/pins_TEENSYLU.h | 5 ++++- 25 files changed, 97 insertions(+), 25 deletions(-) diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 66adfb2fa7..f296f1ba3e 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -103,7 +103,10 @@ #define SDSS 53 #define SD_DETECT_PIN 39 //#define LED_PIN 8 -#define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需要PWM FAN,则需要将FAN_PIN置为7,LED_PIN置为8 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需要PWM FAN,则需要将FAN_PIN置为7,LED_PIN置为8 +#endif //#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered //#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index 2d0db15825..bcb0f77570 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -128,7 +128,10 @@ // #define SDSS 53 #define LED_PIN 13 -#define CASE_LIGHT_PIN 2 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 2 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index 4d7a980050..db50dddc7d 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -98,7 +98,10 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 2 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 2 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index d976e09816..f3551114e2 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -113,7 +113,10 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 2 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 2 +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index 78dd88809f..3bee7e5f1a 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -132,7 +132,10 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 45 // Try the keypad connector + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 45 // Try the keypad connector +#endif // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 351691a09e..dbe473ddb9 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -93,4 +93,7 @@ #define STAT_LED_RED_PIN 23 #define STAT_LED_BLUE_PIN 26 -#define CASE_LIGHT_PIN 51 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 51 +#endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 430fa170e1..630d993d21 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -129,7 +129,10 @@ // #define SDSS 77 #define LED_PIN 13 -#define CASE_LIGHT_PIN 9 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 9 +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 6e8463d0bd..ed5b008bf8 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -143,7 +143,10 @@ // #define SDSS 53 #define LED_PIN 13 -#define CASE_LIGHT_PIN 9 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 9 +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index dec72b8ea7..7a61053069 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -144,7 +144,10 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 4 -#define CASE_LIGHT_PIN 46 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 46 +#endif #ifndef FILWIDTH_PIN #define FILWIDTH_PIN 3 // Analog Input diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 69d2ac2088..974e9ad8b8 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -44,7 +44,9 @@ #define RAMPS_D9_PIN 8 #define MOSFET_D_PIN 12 -#define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header +#endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 454311b7cc..9939211796 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -102,7 +102,9 @@ #undef PS_ON_PIN // 12 #define PS_ON_PIN 81 // External Power Supply -#define CASE_LIGHT_PIN 44 // Hardware PWM +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 44 // Hardware PWM +#endif // This board has headers for Z-min, Z-max and IND_S_5V *but* as the bq team // decided to ship the printer only with the probe and no additional Z-min diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 8993d0ff57..c95db793c1 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -172,7 +172,9 @@ #define PS_ON_PIN 12 #endif -#define CASE_LIGHT_PIN 5 +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 5 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 4e62c67aaf..d9286e4a01 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -175,7 +175,9 @@ #define PS_ON_PIN 12 #endif -#define CASE_LIGHT_PIN 8 +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 8 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 3846a7649e..2a789a2167 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -134,12 +134,16 @@ // // Misc. Functions // -#define CASE_LIGHT_PIN 5 #define SDSS 53 + #ifndef LED_PIN #define LED_PIN 13 #endif +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 5 +#endif + #define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 4 // Pullup! diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h index 057b51a584..0d5929b714 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h @@ -38,7 +38,7 @@ #define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 // Other Mods -#define CASE_LIGHT_PIN 11 // PB5 ** Pin24 ** PWM11 + #define SERVO3_PIN 12 // PB6 ** Pin25 ** D12 #define PS_ON_PIN 2 // X+ // PE4 ** Pin6 ** PWM2 **MUST BE HARDWARE PWM #define FILWIDTH_PIN 15 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup! @@ -54,6 +54,10 @@ #define RGB_LED_B_PIN 52 #endif +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 11 // PB5 ** Pin24 ** PWM11 +#endif + #include "pins_MKS_BASE_common.h" /* diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index 0323366944..b3d1a7ca63 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -106,7 +106,10 @@ #define SDPOWER_PIN 48 #define SDSS 53 #define LED_PIN 13 -#define CASE_LIGHT_PIN 45 // Hardware PWM + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 45 // Hardware PWM +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 4bf10d7399..fd220dc5b7 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -153,7 +153,10 @@ #define LED_PIN 13 #define PS_ON_PIN 45 #define KILL_PIN 46 -#define CASE_LIGHT_PIN 45 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 45 +#endif // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index 8cc588a2f9..4e666b78ce 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -111,7 +111,10 @@ #define LED_PIN 13 #define PS_ON_PIN 12 #define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. -#define CASE_LIGHT_PIN 8 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 8 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index d2114ea433..03d5ebef19 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -216,7 +216,9 @@ // Case Light -#define CASE_LIGHT_PIN GPIO_PB1_J20_5 +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN GPIO_PB1_J20_5 +#endif // 2MB SPI Flash #define SPI_FLASH_SS 52 // D52 PB21 diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index 0d2449ae6e..dd00e6f42b 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -106,7 +106,10 @@ // #define SDSS 17 #define DEBUG_PIN 0 -#define CASE_LIGHT_PIN 16 // Hardware PWM + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 16 // Hardware PWM +#endif // RS485 pins #define TX_ENABLE_PIN 12 diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index 9dc9f2808b..f53563cdec 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -102,7 +102,10 @@ // Misc. Functions // #define PS_ON_PIN 15 -#define CASE_LIGHT_PIN 15 // Hardware PWM + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 15 // Hardware PWM +#endif // A pin for debugging #define DEBUG_PIN 0 diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 67a9762fa0..a3279eb8e6 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -104,7 +104,10 @@ // #define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support #define PS_ON_PIN 19 -#define CASE_LIGHT_PIN 15 // Hardware PWM + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 15 // Hardware PWM +#endif // A pin for debugging #define DEBUG_PIN -1 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index b9272c7211..810d916ccf 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -84,7 +84,10 @@ // #define SDSS -1 #define LED_PIN -1 -#define CASE_LIGHT_PIN PA8 // 8 + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN PA8 // 8 +#endif #define PS_ON_PIN -1 #define KILL_PIN PD6 // LED strip 24v diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index eb116ee3e8..f72cb2bfd3 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -160,7 +160,10 @@ #define SDSS 20 // B0 #define LED_PIN 6 // D6 #define PS_ON_PIN 27 // B7 -#define CASE_LIGHT_PIN 1 // D1 PWM2B MUST BE HARDWARE PWM + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 1 // D1 PWM2B MUST BE HARDWARE PWM +#endif // // LCD / Controller diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index 05f433cb89..5061b849cf 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -134,7 +134,10 @@ // Misc. Functions // #define SDSS 20 // B0 JP31-6 -#define CASE_LIGHT_PIN 0 // D0 IO-14 PWM0B + +#ifndef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 0 // D0 IO-14 PWM0B +#endif // // LCD / Controller From c262b9c5a36e1fb8ffa075f518b8e6a16eda07c4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 8 May 2020 00:03:24 +0000 Subject: [PATCH 0416/1454] [cron] Bump distribution date (2020-05-08) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5b3fe05901..b98008b95e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-07" + #define STRING_DISTRIBUTION_DATE "2020-05-08" #endif /** From a2153c15eef903181afe522dfd719dc6aed90316 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Thu, 7 May 2020 23:15:12 -0700 Subject: [PATCH 0417/1454] Add TMC driver HW serial defines (#17909) --- Marlin/src/core/drivers.h | 1 + Marlin/src/inc/Conditionals_post.h | 3 +++ Marlin/src/module/stepper/trinamic.cpp | 22 ++++++++++++--------- buildroot/share/tests/STM32F103RC_btt-tests | 6 +++++- buildroot/share/tests/STM32F103RE_btt-tests | 4 +++- 5 files changed, 25 insertions(+), 11 deletions(-) diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 37654dc11f..707926791b 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -131,6 +131,7 @@ #define AXIS_HAS_RXTX AXIS_HAS_UART +#define AXIS_HAS_HW_SERIAL(A) ( AXIS_HAS_UART(A) && defined(A##_HARDWARE_SERIAL) ) #define AXIS_HAS_SW_SERIAL(A) ( AXIS_HAS_UART(A) && !defined(A##_HARDWARE_SERIAL) ) #define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index f66c2f16ad..26cad87979 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1549,6 +1549,9 @@ #define HAS_E_STEPPER_ENABLE 1 #endif +#if ANY_AXIS_HAS(HW_SERIAL) + #define HAS_TMC_HW_SERIAL 1 +#endif #if ANY_AXIS_HAS(SW_SERIAL) #define HAS_TMC_SW_SERIAL 1 #endif diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index e2bf706bf1..ed238ede7d 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -318,15 +318,19 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; void tmc_serial_begin() { - struct { - const void *ptr[TMCAxis::TOTAL]; - bool began(const TMCAxis a, const void * const p) { - LOOP_L_N(i, a) if (p == ptr[i]) return true; - ptr[a] = p; return false; - }; - } sp_helper; - #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ - A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) + #if HAS_TMC_HW_SERIAL + struct { + const void *ptr[TMCAxis::TOTAL]; + bool began(const TMCAxis a, const void * const p) { + LOOP_L_N(i, a) if (p == ptr[i]) return true; + ptr[a] = p; return false; + }; + } sp_helper; + + #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ + A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) + #endif + #if AXIS_HAS_UART(X) #ifdef X_HARDWARE_SERIAL HW_SERIAL_BEGIN(X); diff --git a/buildroot/share/tests/STM32F103RC_btt-tests b/buildroot/share/tests/STM32F103RC_btt-tests index 8805c748af..8780eb535c 100644 --- a/buildroot/share/tests/STM32F103RC_btt-tests +++ b/buildroot/share/tests/STM32F103RC_btt-tests @@ -13,7 +13,11 @@ restore_configs opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_E3_V1_0 opt_set SERIAL_PORT 1 opt_set SERIAL_PORT_2 -1 -exec_test $1 $2 "BigTreeTech SKR Mini E3 - Basic Configuration" +opt_set X_DRIVER_TYPE TMC2209 +opt_set Y_DRIVER_TYPE TMC2209 +opt_set Z_DRIVER_TYPE TMC2209 +opt_set E_DRIVER_TYPE TMC2209 +exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - Basic Config with TMC2209 HW Serial" # clean up restore_configs diff --git a/buildroot/share/tests/STM32F103RE_btt-tests b/buildroot/share/tests/STM32F103RE_btt-tests index 77751d776e..9a829a553e 100644 --- a/buildroot/share/tests/STM32F103RE_btt-tests +++ b/buildroot/share/tests/STM32F103RE_btt-tests @@ -13,7 +13,9 @@ restore_configs opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP opt_set SERIAL_PORT 1 opt_set SERIAL_PORT_2 -1 -exec_test $1 $2 "BigTreeTech SKR E3 DIP v1.0 - Basic Configuration" +opt_set X_DRIVER_TYPE TMC2209 +opt_set Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "BigTreeTech SKR E3 DIP v1.0 - Basic Config with mixed TMC Drivers" # clean up restore_configs From 703e97b7af7da222c8d6a301600712678ea2d187 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Thu, 7 May 2020 23:19:28 -0700 Subject: [PATCH 0418/1454] Support TMCStepper with MKS Robin Pro (#17908) --- .github/workflows/test-builds.yml | 1 + buildroot/share/tests/mks_robin_pro-tests | 16 ++++++++++++++++ platformio.ini | 5 +++-- 3 files changed, 20 insertions(+), 2 deletions(-) create mode 100644 buildroot/share/tests/mks_robin_pro-tests diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index f08032c2de..6a75cd4931 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -59,6 +59,7 @@ jobs: - FYSETC_S6 - malyan_M300 - mks_robin_lite + - mks_robin_pro # Put lengthy tests last diff --git a/buildroot/share/tests/mks_robin_pro-tests b/buildroot/share/tests/mks_robin_pro-tests new file mode 100644 index 0000000000..4b437e0e03 --- /dev/null +++ b/buildroot/share/tests/mks_robin_pro-tests @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin Pro +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin_Pro +opt_set SDCARD_CONNECTION LCD +opt_set X_DRIVER_TYPE TMC2209 +opt_set Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "MKS Robin Pro with TMC Drivers " + +# cleanup +restore_configs diff --git a/platformio.ini b/platformio.ini index a2c587ebc9..1dbb9a6817 100644 --- a/platformio.ini +++ b/platformio.ini @@ -558,11 +558,12 @@ platform = ststm32 board = genericSTM32F103ZE extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_pro.py build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DSTM32_XL_DENSITY + ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_XL_DENSITY build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} -lib_ignore = Adafruit NeoPixel, SPI, TMCStepper + SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +lib_ignore = Adafruit NeoPixel, SPI # # MKS Robin E3D (STM32F103RCT6) and From 34a2fd7b09f524ea124492bd465dcd62a3b3d16f Mon Sep 17 00:00:00 2001 From: George Fu Date: Fri, 8 May 2020 14:24:27 +0800 Subject: [PATCH 0419/1454] DGUS minor fixups (#17901) --- Marlin/Configuration.h | 2 ++ Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 22 ++++++++++--------- .../extui/lib/dgus/fysetc/DGUSDisplayDef.cpp | 4 +++- .../extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp | 4 +++- 4 files changed, 20 insertions(+), 12 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index de61230a6f..1da43df24c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2077,6 +2077,8 @@ // // DGUS Touch Display with DWIN OS. (Choose one.) +// ORIGIN : https://www.aliexpress.com/item/32993409517.html +// FYSETC : https://www.aliexpress.com/item/32961471929.html // //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index ccaef782a6..24a4ed0fa1 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -734,10 +734,10 @@ void DGUSScreenVariableHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ default: break; case 1: TERN_(PRINTCOUNTER, print_job_timer.initStats()); - queue.enqueue_now_P(PSTR("M502\nM500")); + queue.inject_P(PSTR("M502\nM500")); break; - case 2: queue.enqueue_now_P(PSTR("M501")); break; - case 3: queue.enqueue_now_P(PSTR("M500")); break; + case 2: queue.inject_P(PSTR("M501")); break; + case 3: queue.inject_P(PSTR("M500")); break; } } @@ -851,14 +851,16 @@ void DGUSScreenVariableHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable } #endif -void DGUSScreenVariableHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { - DEBUG_ECHOLNPGM("HandleProbeOffsetZChanged"); +#if HAS_BED_PROBE + void DGUSScreenVariableHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { + DEBUG_ECHOLNPGM("HandleProbeOffsetZChanged"); - const float offset = float(int16_t(swap16(*(uint16_t*)val_ptr))) / 100.0f; - ExtUI::setZOffset_mm(offset); - ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel - return; -} + const float offset = float(int16_t(swap16(*(uint16_t*)val_ptr))) / 100.0f; + ExtUI::setZOffset_mm(offset); + ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + return; + } +#endif #if ENABLED(BABYSTEPPING) void DGUSScreenVariableHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp index b9f7c8543d..23664dc1f8 100644 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp @@ -327,7 +327,9 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, DGUSScreenVariableHandler::ScreenChangeHook, nullptr), VPHELPER(VP_SCREENCHANGE_ASK, nullptr, DGUSScreenVariableHandler::ScreenChangeHookIfIdle, nullptr), - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, DGUSScreenVariableHandler::ScreenChangeHookIfSD, nullptr), + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, DGUSScreenVariableHandler::ScreenChangeHookIfSD, nullptr), + #endif VPHELPER(VP_CONFIRMED, nullptr, DGUSScreenVariableHandler::ScreenConfirmedOK, nullptr), VPHELPER(VP_TEMP_ALL_OFF, nullptr, &DGUSScreenVariableHandler::HandleAllHeatersOff, nullptr), diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp index ab5b453855..62cd67d2cb 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp @@ -330,7 +330,9 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, DGUSScreenVariableHandler::ScreenChangeHook, nullptr), VPHELPER(VP_SCREENCHANGE_ASK, nullptr, DGUSScreenVariableHandler::ScreenChangeHookIfIdle, nullptr), - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, DGUSScreenVariableHandler::ScreenChangeHookIfSD, nullptr), + #if ENABLED(SDSUPPORT) + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, DGUSScreenVariableHandler::ScreenChangeHookIfSD, nullptr), + #endif VPHELPER(VP_CONFIRMED, nullptr, DGUSScreenVariableHandler::ScreenConfirmedOK, nullptr), VPHELPER(VP_TEMP_ALL_OFF, nullptr, &DGUSScreenVariableHandler::HandleAllHeatersOff, nullptr), From 8fd3af0c79e59b464df8cdaf9ce227d73901c959 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 8 May 2020 08:26:33 +0200 Subject: [PATCH 0420/1454] Fix UBL mesh edit grid display (#17897) --- Marlin/src/lcd/menu/menu_ubl.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 521487c3de..fa0c5d21c4 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -438,8 +438,6 @@ void sync_plan_position(); void _lcd_ubl_output_map_lcd() { - if (planner.movesplanned()) return; - static int16_t step_scaler = 0; if (ui.use_click()) return _lcd_ubl_map_lcd_edit_cmd(); @@ -484,7 +482,8 @@ void _lcd_ubl_output_map_lcd() { if (ui.should_draw()) { ui.ubl_plot(x_plot, y_plot); - ubl_map_move_to_xy(); // Move to new location + if (!planner.movesplanned()) + ubl_map_move_to_xy(); // Move to new location } } From 8f3d17699aeccd04ca23b933e43b4aad28e66c42 Mon Sep 17 00:00:00 2001 From: Bob Kuhn Date: Fri, 8 May 2020 02:43:53 -0500 Subject: [PATCH 0421/1454] Init all ESP01 (module) WIFI pins (#17679) --- Marlin/src/HAL/shared/esp_wifi.cpp | 10 +++++++++- Marlin/src/pins/pinsDebug_list.h | 6 ++++++ Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 14 ++++++++------ 3 files changed, 23 insertions(+), 7 deletions(-) diff --git a/Marlin/src/HAL/shared/esp_wifi.cpp b/Marlin/src/HAL/shared/esp_wifi.cpp index ab073d6f08..5f38ff3128 100644 --- a/Marlin/src/HAL/shared/esp_wifi.cpp +++ b/Marlin/src/HAL/shared/esp_wifi.cpp @@ -23,13 +23,21 @@ #include "../../inc/MarlinConfig.h" #include "Delay.h" -void esp_wifi_init(void) { +void esp_wifi_init(void) { // init ESP01 WIFI module pins + #if PIN_EXISTS(ESP_WIFI_MODULE_GPIO0) + OUT_WRITE(ESP_WIFI_MODULE_GPIO0_PIN, HIGH); + #endif + #if PIN_EXISTS(ESP_WIFI_MODULE_GPIO2) + OUT_WRITE(ESP_WIFI_MODULE_GPIO2_PIN, HIGH); + #endif #if PIN_EXISTS(ESP_WIFI_MODULE_RESET) + delay(1); // power up delay (0.1mS minimum) OUT_WRITE(ESP_WIFI_MODULE_RESET_PIN, LOW); delay(1); OUT_WRITE(ESP_WIFI_MODULE_RESET_PIN, HIGH); #endif #if PIN_EXISTS(ESP_WIFI_MODULE_ENABLE) + delay(1); // delay after reset released (0.1mS minimum) OUT_WRITE(ESP_WIFI_MODULE_ENABLE_PIN, HIGH); #endif } diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index bb7ececa92..2ffa709a6d 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -1415,3 +1415,9 @@ #if PIN_EXISTS(ESP_WIFI_MODULE_ENABLE) REPORT_NAME_DIGITAL(__LINE__, ESP_WIFI_MODULE_ENABLE_PIN) #endif +#if PIN_EXISTS(ESP_WIFI_MODULE_GPIO0) + REPORT_NAME_DIGITAL(__LINE__, ESP_WIFI_MODULE_GPIO0_PIN) +#endif +#if PIN_EXISTS(ESP_WIFI_MODULE_GPIO2) + REPORT_NAME_DIGITAL(__LINE__, ESP_WIFI_MODULE_GPIO2_PIN) +#endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 8d68ca3f9f..8eadf523f3 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -340,13 +340,15 @@ /** * _____ * TX | 1 2 | GND Enable PG1 // Must be high for module to run - * Enable | 3 4 | GPIO2 Reset PG0 // Leave as unused (OK to leave floating) - * Reset | 5 6 | GPIO0 GPIO2 PF15 // Leave as unused (best to leave floating) - * 3.3V| 7 8 | RX GPIO0 PF14 // Leave as unused (best to leave floating) + * Enable | 3 4 | GPIO2 Reset PG0 // active low, probably OK to leave floating + * Reset | 5 6 | GPIO0 GPIO2 PF15 // must be high (ESP3D software configures this with a pullup so OK to leave as floating) + * 3.3V| 7 8 | RX GPIO0 PF14 // Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) *  ̄ ̄ * W1 */ -#define ESP_WIFI_MODULE_COM 6 // Must also set SERIAL_PORT or SERIAL_PORT_2 to this -#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 -#define ESP_WIFI_MODULE_RESET_PIN -1 +#define ESP_WIFI_MODULE_COM 6 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_RESET_PIN PG0 #define ESP_WIFI_MODULE_ENABLE_PIN PG1 +#define ESP_WIFI_MODULE_GPIO0_PIN PF14 +#define ESP_WIFI_MODULE_GPIO2_PIN PF15 From a95a60c7ea546fb1a2506c5bd0a4535d193cacb8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 9 May 2020 00:07:15 +0000 Subject: [PATCH 0422/1454] [cron] Bump distribution date (2020-05-09) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b98008b95e..399d7f9b09 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-08" + #define STRING_DISTRIBUTION_DATE "2020-05-09" #endif /** From 60be3b19be74bc993cc5ea29aefd62ae8d2e7a2f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 10 May 2020 00:03:47 +0000 Subject: [PATCH 0423/1454] [cron] Bump distribution date (2020-05-10) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 399d7f9b09..88c579aee3 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-09" + #define STRING_DISTRIBUTION_DATE "2020-05-10" #endif /** From 2af270ca42d73f90f4d3bdf22f5bc15073b89194 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 9 May 2020 21:24:15 -0700 Subject: [PATCH 0424/1454] Fix M115_GEOMETRY_REPORT extra commas (#17933) --- Marlin/src/gcode/host/M115.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 6e75388beb..b641be8004 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -134,11 +134,11 @@ void GcodeSuite::M115() { "area:{" "full:{" "min:{x:", lmin.x, ",y:", lmin.y, ",z:", lmin.z, "}," - "max:{x:", lmax.x, ",y:", lmax.y, ",z:", lmax.z, "}," + "max:{x:", lmax.x, ",y:", lmax.y, ",z:", lmax.z, "}" "}," "work:{" "min:{x:", wmin.x, ",y:", wmin.y, ",z:", wmin.z, "}," - "max:{x:", wmax.x, ",y:", wmax.y, ",z:", wmax.z, "}," + "max:{x:", wmax.x, ",y:", wmax.y, ",z:", wmax.z, "}", "}" "}" ); From 209fd2d0cb8bc7a7aa94206df2aac08cdb569c8d Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 9 May 2020 21:25:18 -0700 Subject: [PATCH 0425/1454] Fix SERIAL_ECHO forever bug (#17932) --- Marlin/src/core/serial.h | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index dcae748057..5f800c32cf 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -184,13 +184,13 @@ extern uint8_t marlin_debug_flags; #define _SELP_21(a,b,V...) do{ _SEP_2(a,b); _SELP_19(V); }while(0) #define _SELP_22(a,b,V...) do{ _SEP_2(a,b); _SELP_20(V); }while(0) #define _SELP_23(a,b,V...) do{ _SEP_2(a,b); _SELP_21(V); }while(0) -#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0) // Eat two args, pass the rest up -#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(1) // Eat two args, pass the rest up -#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(2) // Eat two args, pass the rest up -#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(3) // Eat two args, pass the rest up -#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(4) // Eat two args, pass the rest up -#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(5) // Eat two args, pass the rest up -#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(6) // Eat two args, pass the rest up +#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0) +#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(0) +#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(0) +#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(0) +#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(0) +#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(0) +#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(0) // Eat two args, pass the rest up #define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) @@ -220,13 +220,13 @@ extern uint8_t marlin_debug_flags; #define _SELP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_19_P(V); }while(0) #define _SELP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_20_P(V); }while(0) #define _SELP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_21_P(V); }while(0) -#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0) // Eat two args, pass the rest up -#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(1) // Eat two args, pass the rest up -#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(2) // Eat two args, pass the rest up -#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(3) // Eat two args, pass the rest up -#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(4) // Eat two args, pass the rest up -#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(5) // Eat two args, pass the rest up -#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(6) // Eat two args, pass the rest up +#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0) +#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(0) +#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(0) +#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(0) +#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(0) +#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(0) +#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(0) // Eat two args, pass the rest up #define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V) From 37f86d9e08d3ec3f39e6686bc5e5b478c2892931 Mon Sep 17 00:00:00 2001 From: Brais Fortes Date: Sun, 10 May 2020 06:26:06 +0200 Subject: [PATCH 0426/1454] Update Galician language (#17929) --- Marlin/src/lcd/language/language_gl.h | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index d747b78183..e819d9075f 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -49,6 +49,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch."); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); @@ -263,6 +264,10 @@ namespace Language_gl { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apagar"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Auto-Sint. PID"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Auto-Sint. PID *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Fin Auto-Sint PID"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-Sint. fallida. Extrusor danado."); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-Sint. fallida. Temperatura moi alta."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Auto-Sint. fallida. Tempo excedido."); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); @@ -298,6 +303,8 @@ namespace Language_gl { PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrac."); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-viaxe"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frecuencia max"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Avance min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); @@ -368,11 +375,22 @@ namespace Language_gl { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retracción"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lonxitude Retracción"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Cambio Extra"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lonxitude de Purga"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Ferramenta"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocidade prim."); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de Retracción"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Extrusor Est."); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Vel. Recuperación"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Vel. Ventilador"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Tempo Ventilador"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Cambio Ferramenta"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Cambio Automático"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Último Extrusor"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Cambio a *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar Filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar Filamento *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar Filamento"); From 7a9bb6bc864c3c0d4fa254cc59dd8e303daac497 Mon Sep 17 00:00:00 2001 From: Alexander Gee Date: Sat, 9 May 2020 23:35:26 -0500 Subject: [PATCH 0427/1454] Remove old M73 / SD comment (#17928) --- Marlin/src/gcode/lcd/M73.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index 347c42c442..8e87d2e2d5 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -33,9 +33,6 @@ * * Example: * M73 P25 ; Set progress to 25% - * - * Notes: - * This has no effect during an SD print job */ void GcodeSuite::M73() { if (parser.seen('P')) From 91fe0e1022ee740262792d6a857c7226745f8c75 Mon Sep 17 00:00:00 2001 From: Gurmeet Athwal Date: Sun, 10 May 2020 10:06:04 +0530 Subject: [PATCH 0428/1454] Fix line ending in M360 (#17917) --- Marlin/src/gcode/host/M360.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 5c00be30b4..63a0b6dfc4 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -93,7 +93,7 @@ void GcodeSuite::M360() { config_line(PSTR("SupportG10G11"), ENABLED(FWRETRACT)); #if ENABLED(FWRETRACT) PGMSTR(RET_STR, "Retraction"); - PGMSTR(UNRET_STR, "RetractionUndo"), + PGMSTR(UNRET_STR, "RetractionUndo"); PGMSTR(SPEED_STR, "Speed"); // M10 Retract with swap (long) moves config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR); From 52aa459a2dc08a8f803ad9ffb7aa173dc449637f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 00:12:56 -0500 Subject: [PATCH 0429/1454] Improved EEPROM boot error (#17916) --- Marlin/src/lcd/language/language_en.h | 7 +- Marlin/src/lcd/menu/menu.cpp | 16 +-- Marlin/src/lcd/menu/menu.h | 5 - Marlin/src/lcd/menu/menu_advanced.cpp | 15 +-- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 4 +- Marlin/src/lcd/menu/menu_configuration.cpp | 13 +-- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 4 +- Marlin/src/lcd/menu/menu_main.cpp | 2 +- Marlin/src/lcd/menu/menu_mixer.cpp | 2 +- Marlin/src/lcd/ultralcd.cpp | 107 ++++++++++++------- Marlin/src/lcd/ultralcd.h | 40 +++++-- Marlin/src/module/configuration_store.cpp | 14 +-- 13 files changed, 125 insertions(+), 106 deletions(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 8249dba743..df27de57a5 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -328,9 +328,9 @@ namespace Language_en { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Load Settings"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restore Defaults"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initialize EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: EEPROM Index"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: EEPROM Version"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Media Update"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reset Printer"); @@ -344,6 +344,7 @@ namespace Language_en { PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Print"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reset"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignore"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancel"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Done"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Back"); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 39e8899313..013186a92a 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -34,10 +34,6 @@ #include "../../libs/buzzer.h" #endif -#if ENABLED(EEPROM_SETTINGS) - #include "../../module/configuration_store.h" -#endif - #if WATCH_HOTENDS || WATCH_BED #include "../../module/temperature.h" #endif @@ -228,7 +224,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co if (on_status_screen()) doubleclick_expire_ms = millis() + DOUBLECLICK_MAX_INTERVAL; } - else if (screen == status_screen && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { + else if (on_status_screen() && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) screen = TERN(BABYSTEP_ZPROBE_OFFSET, lcd_babystep_zoffset, lcd_babystep_z); @@ -245,7 +241,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co encoderPosition = encoder; encoderTopLine = top; screen_items = items; - if (screen == status_screen) { + if (on_status_screen()) { defer_status_screen(false); TERN_(AUTO_BED_LEVELING_UBL, ubl.lcd_map_control = false); screen_history_depth = 0; @@ -256,7 +252,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co // Re-initialize custom characters that may be re-used #if HAS_CHARACTER_LCD if (TERN1(AUTO_BED_LEVELING_UBL, !ubl.lcd_map_control)) - set_custom_characters(screen == status_screen ? CHARSET_INFO : CHARSET_MENU); + set_custom_characters(on_status_screen() ? CHARSET_INFO : CHARSET_MENU); #endif refresh(LCDVIEW_CALL_REDRAW_NEXT); @@ -383,11 +379,6 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #endif // BABYSTEP_ZPROBE_OFFSET -#if ENABLED(EEPROM_SETTINGS) - void lcd_store_settings() { ui.completion_feedback(settings.save()); } - void lcd_load_settings() { ui.completion_feedback(settings.load()); } -#endif - void _lcd_draw_homing() { constexpr uint8_t line = (LCD_HEIGHT - 1) / 2; if (ui.should_draw()) MenuItem_static::draw(line, GET_TEXT(MSG_LEVEL_BED_HOMING)); @@ -416,6 +407,7 @@ void MenuItem_confirm::select_screen(PGM_P const yes, PGM_P const no, selectFunc if (got_click || ui.should_draw()) { draw_select_screen(yes, no, ui_selection, pref, string, suff); if (got_click) { ui_selection ? yesFunc() : noFunc(); } + ui.defer_status_screen(); } } diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index fc5ff36987..9b2b318e7d 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -589,11 +589,6 @@ void _lcd_draw_homing(); #endif #endif -#if ENABLED(EEPROM_SETTINGS) - void lcd_store_settings(); - void lcd_load_settings(); -#endif - #if ENABLED(POWER_LOSS_RECOVERY) void menu_job_recovery(); #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 0f91e1de1d..aec0b867f1 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -47,7 +47,7 @@ #include "../../feature/runout.h" #endif -#if ENABLED(EEPROM_SETTINGS) && DISABLED(SLIM_LCD_MENUS) +#if ENABLED(SD_FIRMWARE_UPDATE) #include "../../module/configuration_store.h" #endif @@ -97,10 +97,6 @@ void menu_cancelobject(); #endif -#if ENABLED(SD_FIRMWARE_UPDATE) - #include "../../module/configuration_store.h" -#endif - #if DISABLED(NO_VOLUMETRICS) || ENABLED(ADVANCED_PAUSE_FEATURE) // // Advanced Settings > Filament @@ -591,13 +587,8 @@ void menu_advanced_settings() { #if ENABLED(EEPROM_SETTINGS) && DISABLED(SLIM_LCD_MENUS) CONFIRM_ITEM(MSG_INIT_EEPROM, MSG_BUTTON_INIT, MSG_BUTTON_CANCEL, - []{ - const bool inited = settings.init_eeprom(); - ui.completion_feedback(inited); - UNUSED(inited); - }, - ui.goto_previous_screen, - GET_TEXT(MSG_INIT_EEPROM), (PGM_P)nullptr, PSTR("?") + ui.init_eeprom, ui.goto_previous_screen, + GET_TEXT(MSG_INIT_EEPROM), (const char *)nullptr, PSTR("?") ); #endif diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index fb0087ad0e..fca5ca8af9 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -86,7 +86,7 @@ static inline void _lcd_level_bed_corners_homing() { ui.goto_previous_screen_no_defer(); } , GET_TEXT(TERN(LEVEL_CENTER_TOO, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) - , (PGM_P)nullptr, PSTR("?") + , (const char*)nullptr, PSTR("?") ); }); ui.set_selection(true); diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 5192c596da..fc13ab8031 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -279,8 +279,8 @@ void menu_bed_leveling() { #endif #if ENABLED(EEPROM_SETTINGS) - ACTION_ITEM(MSG_LOAD_EEPROM, lcd_load_settings); - ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); + ACTION_ITEM(MSG_LOAD_EEPROM, ui.load_settings); + ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 7c71dd2a1b..da6b3ea1cb 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -30,8 +30,6 @@ #include "menu.h" -#include "../../module/configuration_store.h" - #if HAS_FILAMENT_SENSOR #include "../../feature/runout.h" #endif @@ -174,7 +172,7 @@ void menu_advanced_settings(); EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_Y, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_Z, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); #if ENABLED(EEPROM_SETTINGS) - ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); + ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif END_MENU(); } @@ -335,7 +333,7 @@ void menu_advanced_settings(); EDIT_ITEM(int3, MSG_BED, &ui.preheat_bed_temp[material], BED_MINTEMP, BED_MAX_TARGET); #endif #if ENABLED(EEPROM_SETTINGS) - ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); + ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif END_MENU(); } @@ -439,12 +437,11 @@ void menu_configuration() { #endif #if ENABLED(EEPROM_SETTINGS) - ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); - if (!busy) ACTION_ITEM(MSG_LOAD_EEPROM, lcd_load_settings); + ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); + if (!busy) ACTION_ITEM(MSG_LOAD_EEPROM, ui.load_settings); #endif - if (!busy) - ACTION_ITEM(MSG_RESTORE_DEFAULTS, []{ settings.reset(); ui.completion_feedback(); }); + if (!busy) ACTION_ITEM(MSG_RESTORE_DEFAULTS, ui.reset_settings); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 633206ba87..381606bd14 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -126,8 +126,8 @@ void menu_delta_calibrate() { #if ENABLED(DELTA_AUTO_CALIBRATION) GCODES_ITEM(MSG_DELTA_AUTO_CALIBRATE, PSTR("G33")); #if ENABLED(EEPROM_SETTINGS) - ACTION_ITEM(MSG_STORE_EEPROM, lcd_store_settings); - ACTION_ITEM(MSG_LOAD_EEPROM, lcd_load_settings); + ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); + ACTION_ITEM(MSG_LOAD_EEPROM, ui.load_settings); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index f882fe6868..6cc20b2fa1 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -103,7 +103,7 @@ void menu_main() { MenuItem_confirm::select_screen( GET_TEXT(MSG_BUTTON_STOP), GET_TEXT(MSG_BACK), ui.abort_print, ui.goto_previous_screen, - GET_TEXT(MSG_STOP_PRINT), (PGM_P)nullptr, PSTR("?") + GET_TEXT(MSG_STOP_PRINT), (const char *)nullptr, PSTR("?") ); }); #endif diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index e830b49a99..764e0423e2 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -265,7 +265,7 @@ void menu_mixer() { ui.return_to_status(); }, ui.goto_previous_screen, - GET_TEXT(MSG_RESET_VTOOLS), (PGM_P)nullptr, PSTR("?") + GET_TEXT(MSG_RESET_VTOOLS), (const char *)nullptr, PSTR("?") ); #if ENABLED(GRADIENT_MIX) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 1193a2fee7..9e0a5580f7 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -95,6 +95,7 @@ MarlinUI ui; #include "lcdprint.h" #include "../sd/cardreader.h" +#include "../module/configuration_store.h" #include "../module/temperature.h" #include "../module/planner.h" #include "../module/motion.h" @@ -879,11 +880,7 @@ void MarlinUI::update() { // This runs every ~100ms when idling often enough. // Instead of tracking changes just redraw the Status Screen once per second. if (on_status_screen() && !lcd_status_update_delay--) { - lcd_status_update_delay = 9 - #if HAS_GRAPHICAL_LCD - + 3 - #endif - ; + lcd_status_update_delay = TERN(HAS_GRAPHICAL_LCD, 12, 9); max_display_update_time--; refresh(LCDVIEW_REDRAW_NOW); } @@ -1167,11 +1164,7 @@ void MarlinUI::update() { WRITE(SHIFT_CLK, HIGH); WRITE(SHIFT_CLK, LOW); } - #if ENABLED(REPRAPWORLD_KEYPAD) - keypad_buttons = ~val; - #else - buttons = ~val; - #endif + TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; #endif } // next_button_update_ms @@ -1238,7 +1231,7 @@ void MarlinUI::update() { void MarlinUI::finish_status(const bool persist) { - #if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE > 0)) + #if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE) > 0) UNUSED(persist); #endif @@ -1438,18 +1431,10 @@ void MarlinUI::update() { #if HAS_PRINT_PROGRESS MarlinUI::progress_t MarlinUI::_get_progress() { - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - const progress_t p = progress_override & PROGRESS_MASK; - #else - constexpr progress_t p = 0; - #endif - return (p + return ( + TERN0(LCD_SET_PROGRESS_MANUALLY, (progress_override & PROGRESS_MASK)) #if ENABLED(SDSUPPORT) - #if HAS_PRINT_PROGRESS_PERMYRIAD - ?: card.permyriadDone() - #else - ?: card.percentDone() - #endif + ?: TERN(HAS_PRINT_PROGRESS_PERMYRIAD, card.permyriadDone(), card.percentDone()) #endif ); } @@ -1461,29 +1446,14 @@ void MarlinUI::update() { // // Send the status line as a host notification // - void MarlinUI::set_status(const char * const message, const bool) { - #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_notify(message); - #else - UNUSED(message); - #endif + TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); } - void MarlinUI::set_status_P(PGM_P message, const int8_t) { - #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_notify(message); - #else - UNUSED(message); - #endif + TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); } - void MarlinUI::status_printf_P(const uint8_t, PGM_P const message, ...) { - #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_notify(message); - #else - UNUSED(message); - #endif + TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); } #endif // !HAS_DISPLAY @@ -1507,7 +1477,9 @@ void MarlinUI::update() { TERN_(EXTENSIBLE_UI, ExtUI::onMediaRemoved()); // ExtUI response #if PIN_EXISTS(SD_DETECT) set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); - TERN_(HAS_LCD_MENU, return_to_status()); + #if HAS_LCD_MENU + if (!defer_return_to_status) return_to_status(); + #endif #endif } } @@ -1530,3 +1502,56 @@ void MarlinUI::update() { } #endif // SDSUPPORT + +#if HAS_LCD_MENU + void MarlinUI::reset_settings() { settings.reset(); completion_feedback(); } +#endif + +#if ENABLED(EEPROM_SETTINGS) + + #if HAS_LCD_MENU + void MarlinUI::init_eeprom() { + const bool good = settings.init_eeprom(); + completion_feedback(good); + return_to_status(); + } + void MarlinUI::load_settings() { + const bool good = settings.load(); + completion_feedback(good); + } + void MarlinUI::store_settings() { + const bool good = settings.save(); + completion_feedback(good); + } + #endif + + #if DISABLED(EEPROM_AUTO_INIT) + + static inline PGM_P eeprom_err(const uint8_t msgid) { + switch (msgid) { + default: + case 0: return GET_TEXT(MSG_ERR_EEPROM_CRC); + case 1: return GET_TEXT(MSG_ERR_EEPROM_INDEX); + case 2: return GET_TEXT(MSG_ERR_EEPROM_VERSION); + } + } + + void MarlinUI::eeprom_alert(const uint8_t msgid) { + #if HAS_LCD_MENU + editable.uint8 = msgid; + goto_screen([]{ + PGM_P const restore_msg = GET_TEXT(MSG_RESTORE_DEFAULTS); + char msg[utf8_strlen_P(restore_msg) + 1]; + strcpy_P(msg, restore_msg); + MenuItem_confirm::select_screen( + GET_TEXT(MSG_BUTTON_RESET), GET_TEXT(MSG_BUTTON_IGNORE), + init_eeprom, return_to_status, + eeprom_err(editable.uint8), msg, PSTR("?") + ); + }); + #else + set_status_P(eeprom_err(msgid)); + #endif + } + #endif +#endif diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 7df6b42e00..b5e1696239 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -544,14 +544,40 @@ public: #endif - #define LCD_HAS_WAIT_FOR_MOVE EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) + // + // EEPROM: Reset / Init / Load / Store + // + #if HAS_LCD_MENU + static void reset_settings(); + #endif - #if LCD_HAS_WAIT_FOR_MOVE + #if ENABLED(EEPROM_SETTINGS) + #if HAS_LCD_MENU + static void init_eeprom(); + static void load_settings(); + static void store_settings(); + #endif + #if DISABLED(EEPROM_AUTO_INIT) + static void eeprom_alert(const uint8_t msgid); + static inline void eeprom_alert_crc() { eeprom_alert(0); } + static inline void eeprom_alert_index() { eeprom_alert(1); } + static inline void eeprom_alert_version() { eeprom_alert(2); } + #endif + #endif + + // + // Special handling if a move is underway + // + #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) + #define LCD_HAS_WAIT_FOR_MOVE 1 static bool wait_for_move; #else static constexpr bool wait_for_move = false; #endif + // + // Block interaction while under external control + // #if HAS_LCD_MENU && EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) static bool external_control; FORCE_INLINE static void capture() { external_control = true; } @@ -615,12 +641,10 @@ private: #endif #if HAS_SPI_LCD - #if HAS_LCD_MENU - #if LCD_TIMEOUT_TO_STATUS > 0 - static bool defer_return_to_status; - #else - static constexpr bool defer_return_to_status = false; - #endif + #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 + static bool defer_return_to_status; + #else + static constexpr bool defer_return_to_status = false; #endif static void draw_status_screen(); #endif diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index a42aa2d52d..2ebff1f035 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -37,7 +37,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V78" +#define EEPROM_VERSION "V79" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -1367,9 +1367,7 @@ void MarlinSettings::postprocess() { } DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); - #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - LCD_MESSAGEPGM(MSG_ERR_EEPROM_VERSION); - #endif + TERN(EEPROM_AUTO_INIT,,ui.eeprom_alert_version()); eeprom_error = true; } else { @@ -2141,17 +2139,13 @@ void MarlinSettings::postprocess() { if (eeprom_error) { DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)), " Size: ", datasize()); - #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - LCD_MESSAGEPGM(MSG_ERR_EEPROM_INDEX); - #endif + TERN(EEPROM_AUTO_INIT,,ui.eeprom_alert_index()); } else if (working_crc != stored_crc) { eeprom_error = true; DEBUG_ERROR_START(); DEBUG_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); - #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - LCD_MESSAGEPGM(MSG_ERR_EEPROM_CRC); - #endif + TERN(EEPROM_AUTO_INIT,,ui.eeprom_alert_crc()); } else if (!validating) { DEBUG_ECHO_START(); From 71b41c963b617204f45286cddd029d4c1a4c664c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 00:37:19 -0500 Subject: [PATCH 0430/1454] Better EEPROM alert message --- Marlin/src/lcd/menu/menu.cpp | 6 +++++- Marlin/src/lcd/ultralcd.cpp | 2 +- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 013186a92a..dfd55ae682 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -402,7 +402,11 @@ bool MarlinUI::update_selection() { return selection; } -void MenuItem_confirm::select_screen(PGM_P const yes, PGM_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { +void MenuItem_confirm::select_screen( + PGM_P const yes, PGM_P const no, + selectFunc_t yesFunc, selectFunc_t noFunc, + PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/ +) { const bool ui_selection = ui.update_selection(), got_click = ui.use_click(); if (got_click || ui.should_draw()) { draw_select_screen(yes, no, ui_selection, pref, string, suff); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 9e0a5580f7..5ed529df76 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1540,7 +1540,7 @@ void MarlinUI::update() { #if HAS_LCD_MENU editable.uint8 = msgid; goto_screen([]{ - PGM_P const restore_msg = GET_TEXT(MSG_RESTORE_DEFAULTS); + PGM_P const restore_msg = GET_TEXT(MSG_INIT_EEPROM); char msg[utf8_strlen_P(restore_msg) + 1]; strcpy_P(msg, restore_msg); MenuItem_confirm::select_screen( From ba9a9bbe587f21e4bfa3552aa504a16213b6c28f Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 9 May 2020 23:49:30 -0700 Subject: [PATCH 0431/1454] Normalize HAL/STM32 targets (#17904) --- .github/workflows/test-builds.yml | 8 +++-- .../PlatformIO/boards/BigTree_Btt002.json | 1 - .../PlatformIO/boards/BigTree_SKR_Pro.json | 1 - .../share/PlatformIO/boards/FLYF407ZG.json | 1 - .../PlatformIO/boards/blackSTM32F407VET6.json | 1 - buildroot/share/tests/ARMED-tests | 5 ++- buildroot/share/tests/BIGTREE_GTR_V1_0-tests | 4 ++- buildroot/share/tests/BIGTREE_SKR_PRO-tests | 3 +- buildroot/share/tests/FLYF407ZG-tests | 18 ++++++++++ buildroot/share/tests/FYSETC_S6-tests | 2 ++ .../share/tests/STM32F070RB_malyan-tests | 15 ++++++++ .../share/tests/STM32F401VE_STEVAL-tests | 16 +++++++++ buildroot/share/tests/STM32F407VE_black-tests | 1 + buildroot/share/tests/malyan_M300-tests | 1 + buildroot/share/tests/rumba32_f446ve-tests | 17 ++++++++++ buildroot/share/tests/rumba32_mks-tests | 18 ++++++++++ platformio.ini | 34 ++++++++++++------- 17 files changed, 124 insertions(+), 22 deletions(-) create mode 100644 buildroot/share/tests/FLYF407ZG-tests create mode 100644 buildroot/share/tests/STM32F070RB_malyan-tests create mode 100644 buildroot/share/tests/STM32F401VE_STEVAL-tests create mode 100644 buildroot/share/tests/rumba32_f446ve-tests create mode 100644 buildroot/share/tests/rumba32_mks-tests diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 6a75cd4931..22ca222b91 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -52,13 +52,19 @@ jobs: - jgaurora_a5s_a1 - STM32F103VE_longer - STM32F407VE_black + - STM32F401VE_STEVAL + - BIGTREE_BTT002 - BIGTREE_SKR_PRO - BIGTREE_GTR_V1_0 - mks_robin - ARMED - FYSETC_S6 + - STM32F070RB_malyan - malyan_M300 - mks_robin_lite + - FLYF407ZG + - rumba32_f446ve + - rumba32_mks - mks_robin_pro # Put lengthy tests last @@ -72,8 +78,6 @@ jobs: #- STM32F7 # Non-working environment tests - - #- BIGTREE_BTT002 #- at90usb1286_cdc #- at90usb1286_dfu #- STM32F103CB_malyan diff --git a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json index 9012d107bc..ef3333cbb9 100644 --- a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json +++ b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json @@ -14,7 +14,6 @@ "0x3748" ] ], - "ldscript": "stm32f407xg.ld", "mcu": "stm32f407vgt6", "variant": "BIGTREE_BTT002" }, diff --git a/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json b/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json index 1b5aee4b8e..357b3acca9 100644 --- a/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json +++ b/buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json @@ -14,7 +14,6 @@ "0x3748" ] ], - "ldscript": "stm32f407xg.ld", "mcu": "stm32f407zgt6", "variant": "BIGTREE_SKR_PRO_1v1" }, diff --git a/buildroot/share/PlatformIO/boards/FLYF407ZG.json b/buildroot/share/PlatformIO/boards/FLYF407ZG.json index 944dc7a9d8..060b50ee8c 100644 --- a/buildroot/share/PlatformIO/boards/FLYF407ZG.json +++ b/buildroot/share/PlatformIO/boards/FLYF407ZG.json @@ -14,7 +14,6 @@ "0x3748" ] ], - "ldscript": "stm32f407xg.ld", "mcu": "stm32f407zgt6", "variant": "FLY_F407ZG" }, diff --git a/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json b/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json index c55d7cc80a..1778ddaaf0 100644 --- a/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json +++ b/buildroot/share/PlatformIO/boards/blackSTM32F407VET6.json @@ -14,7 +14,6 @@ "0x3748" ] ], - "ldscript": "stm32f407xe.ld", "mcu": "stm32f407vet6", "variant": "MARLIN_F407VE" }, diff --git a/buildroot/share/tests/ARMED-tests b/buildroot/share/tests/ARMED-tests index 44af749a48..e5959a4383 100644 --- a/buildroot/share/tests/ARMED-tests +++ b/buildroot/share/tests/ARMED-tests @@ -9,8 +9,11 @@ set -e # # Build with the default configurations # +restore_configs use_example_configs ArmEd -exec_test $1 $2 "ArmEd Example Configuration" +opt_set X_DRIVER_TYPE TMC2130 +opt_set Y_DRIVER_TYPE TMC2208 +exec_test $1 $2 "ArmEd Example Configuration with mixed TMC Drivers" # clean up restore_configs diff --git a/buildroot/share/tests/BIGTREE_GTR_V1_0-tests b/buildroot/share/tests/BIGTREE_GTR_V1_0-tests index 18a6a75f6f..850aaeacdf 100644 --- a/buildroot/share/tests/BIGTREE_GTR_V1_0-tests +++ b/buildroot/share/tests/BIGTREE_GTR_V1_0-tests @@ -21,7 +21,9 @@ opt_set TEMP_SENSOR_7 1 opt_set E0_AUTO_FAN_PIN PC10 opt_set E1_AUTO_FAN_PIN PC11 opt_set E2_AUTO_FAN_PIN PC12 -exec_test $1 $2 "BigTreeTech GTR 8 Extruders with Auto-Fan" +opt_set X_DRIVER_TYPE TMC2208 +opt_set Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "BigTreeTech GTR 8 Extruders with Auto-Fan and Mixed TMC Drivers" restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 diff --git a/buildroot/share/tests/BIGTREE_SKR_PRO-tests b/buildroot/share/tests/BIGTREE_SKR_PRO-tests index 7623bf3f66..1617275de9 100644 --- a/buildroot/share/tests/BIGTREE_SKR_PRO-tests +++ b/buildroot/share/tests/BIGTREE_SKR_PRO-tests @@ -23,9 +23,10 @@ opt_set TEMP_SENSOR_2 1 opt_set E0_AUTO_FAN_PIN PC10 opt_set E1_AUTO_FAN_PIN PC11 opt_set E2_AUTO_FAN_PIN PC12 +opt_set BLTOUCH Z_SAFE_HOMING opt_set X_DRIVER_TYPE TMC2209 opt_set Y_DRIVER_TYPE TMC2130 -exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders with Auto-Fan and mixed TMC drivers" +exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders, Auto-Fan, BLTOUCH, and mixed TMC drivers" # clean up restore_configs diff --git a/buildroot/share/tests/FLYF407ZG-tests b/buildroot/share/tests/FLYF407ZG-tests new file mode 100644 index 0000000000..f1a65da6cb --- /dev/null +++ b/buildroot/share/tests/FLYF407ZG-tests @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for FLYF407ZG +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_FLYF407ZG +opt_set SERIAL_PORT -1 +opt_set X_DRIVER_TYPE TMC2208 +opt_set Y_DRIVER_TYPE TMC2130 +exec_test $1 $2 "FLYF407ZG Default Config with mixed TMC Drivers" + +# cleanup +restore_configs diff --git a/buildroot/share/tests/FYSETC_S6-tests b/buildroot/share/tests/FYSETC_S6-tests index a9e0331acd..c75629156b 100644 --- a/buildroot/share/tests/FYSETC_S6-tests +++ b/buildroot/share/tests/FYSETC_S6-tests @@ -9,6 +9,8 @@ set -e # Build examples restore_configs use_example_configs FYSETC/S6 +opt_set Y_DRIVER_TYPE TMC2209 +opt_set Z_DRIVER_TYPE TMC2130 exec_test $1 $2 "FYSETC S6 Example" # cleanup diff --git a/buildroot/share/tests/STM32F070RB_malyan-tests b/buildroot/share/tests/STM32F070RB_malyan-tests new file mode 100644 index 0000000000..58237a70eb --- /dev/null +++ b/buildroot/share/tests/STM32F070RB_malyan-tests @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F070RB Malyan M200 v2 +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_MALYAN_M200_V2 +opt_set SERIAL_PORT -1 +exec_test $1 $2 "Malyan M200 v2 Default Config" + +# cleanup +restore_configs diff --git a/buildroot/share/tests/STM32F401VE_STEVAL-tests b/buildroot/share/tests/STM32F401VE_STEVAL-tests new file mode 100644 index 0000000000..2811014c13 --- /dev/null +++ b/buildroot/share/tests/STM32F401VE_STEVAL-tests @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F401VE_STEVAL +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_STEVAL_3DP001V1 +opt_set SERIAL_PORT -1 +exec_test $1 $2 "STM32F401VE_STEVAL Default Config" + +# cleanup +restore_configs diff --git a/buildroot/share/tests/STM32F407VE_black-tests b/buildroot/share/tests/STM32F407VE_black-tests index c35b279b0f..908382ec2a 100755 --- a/buildroot/share/tests/STM32F407VE_black-tests +++ b/buildroot/share/tests/STM32F407VE_black-tests @@ -6,6 +6,7 @@ # exit on first failure set -e +restore_configs use_example_configs STM32/Black_STM32F407VET6 opt_enable BAUD_RATE_GCODE exec_test $1 $2 "Full-featured Sample Black STM32F407VET6 config" diff --git a/buildroot/share/tests/malyan_M300-tests b/buildroot/share/tests/malyan_M300-tests index 31cbabd754..ada60d5584 100755 --- a/buildroot/share/tests/malyan_M300-tests +++ b/buildroot/share/tests/malyan_M300-tests @@ -6,6 +6,7 @@ # exit on first failure set -e +restore_configs use_example_configs "delta/Malyan M300" opt_disable AUTO_BED_LEVELING_3POINT exec_test $1 $2 "Malyan M300 (delta)" diff --git a/buildroot/share/tests/rumba32_f446ve-tests b/buildroot/share/tests/rumba32_f446ve-tests new file mode 100644 index 0000000000..a0286b54a9 --- /dev/null +++ b/buildroot/share/tests/rumba32_f446ve-tests @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for rumba32_f446ve +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_RUMBA32_AUS3D +opt_set SERIAL_PORT -1 +opt_set X_DRIVER_TYPE TMC2130 +exec_test $1 $2 "rumba32_f446ve Default Config with TMC2130" + +# cleanup +restore_configs diff --git a/buildroot/share/tests/rumba32_mks-tests b/buildroot/share/tests/rumba32_mks-tests new file mode 100644 index 0000000000..0180b6d98e --- /dev/null +++ b/buildroot/share/tests/rumba32_mks-tests @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for rumba32_mks +# + +# exit on first failure +set -e + +# Build examples +restore_configs +opt_set MOTHERBOARD BOARD_RUMBA32_MKS +opt_set SERIAL_PORT -1 +opt_set X_DRIVER_TYPE TMC2130 +opt_set Y_DRIVER_TYPE TMC2208 +exec_test $1 $2 "rumba32_mks Default Config with Mixed TMC Drivers" + +# cleanup +restore_configs diff --git a/platformio.ini b/platformio.ini index 1dbb9a6817..99d1a46303 100644 --- a/platformio.ini +++ b/platformio.ini @@ -21,6 +21,7 @@ boards_dir = buildroot/share/PlatformIO/boards default_envs = mega2560 [common] +arduinoststm32_ver = >=4.10700,<4.10800 default_src_filter = + - - + extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-cxxflags.py build_flags = -fmax-errors=5 -g -D__MARLIN_FIRMWARE__ -fmerge-all-constants @@ -470,6 +471,7 @@ src_filter = ${common.default_src_filter} + - -lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL +lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL, SoftwareSerial # # Malyan M300 (STM32F070CB) @@ -676,8 +680,8 @@ lib_ignore = Adafruit NeoPixel # [env:STM32F401VE_STEVAL] platform = ststm32 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = STEVAL_STM32F401VE -platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" @@ -694,15 +698,15 @@ src_filter = ${common.default_src_filter} + # [env:FLYF407ZG] platform = ststm32 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = FLYF407ZG -platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DSTM32F4 -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x8000 -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial +lib_ignore = Adafruit NeoPixel, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial src_filter = ${common.default_src_filter} + @@ -711,10 +715,10 @@ src_filter = ${common.default_src_filter} + # [env:FYSETC_S6] platform = ststm32 -board = fysetc_s6 platform_packages = tool-stm32duino - framework-arduinoststm32@>=3.10700,<4 + framework-arduinoststm32@${common.arduinoststm32_ver} +board = fysetc_s6 build_flags = ${common.build_flags} -DTARGET_STM32F4 -std=gnu++14 -DVECT_TAB_OFFSET=0x10000 @@ -735,8 +739,8 @@ upload_protocol = serial # [env:STM32F407VE_black] platform = ststm32 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = blackSTM32F407VET6 -platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\" @@ -752,8 +756,8 @@ src_filter = ${common.default_src_filter} + # [env:BIGTREE_SKR_PRO] platform = ststm32 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = BigTree_SKR_Pro -platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 @@ -772,7 +776,7 @@ debug_init_break = # [env:BIGTREE_GTR_V1_0] platform = ststm32@>=5.7.0 -platform_packages = framework-arduinoststm32@>=3.10700,<4 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = BigTree_SKR_Pro extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common.build_flags} @@ -794,8 +798,8 @@ src_filter = ${common.default_src_filter} + # [env:BIGTREE_BTT002] platform = ststm32@5.6.0 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = BigTree_Btt002 -platform_packages = framework-arduinoststm32@>=3.10700,<4 build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407VG\" -DTARGET_STM32F4 -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 @@ -883,6 +887,7 @@ debug_tool = jlink # [env:rumba32_f446ve] platform = ststm32 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = rumba32_f446ve build_flags = ${common.build_flags} -DSTM32F4xx @@ -899,7 +904,8 @@ build_flags = ${common.build_flags} -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -Os -lib_ignore = Adafruit NeoPixel + -IMarlin/src/HAL/STM32 +lib_ignore = Adafruit NeoPixel, SoftwareSerial src_filter = ${common.default_src_filter} + monitor_speed = 500000 upload_protocol = dfu @@ -909,6 +915,7 @@ upload_protocol = dfu # [env:rumba32_mks] platform = ststm32 +platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = rumba32_f446ve build_flags = ${common.build_flags} -DSTM32F4xx -DARDUINO_RUMBA32_F446VE -DARDUINO_ARCH_STM32 "-DBOARD_NAME=\"RUMBA32_F446VE\"" @@ -920,8 +927,9 @@ build_flags = ${common.build_flags} -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -Os -lib_ignore = Adafruit NeoPixel -src_filter = ${common.default_src_filter} + + - + -IMarlin/src/HAL/STM32 +lib_ignore = Adafruit NeoPixel, SoftwareSerial +src_filter = ${common.default_src_filter} + upload_protocol = dfu # From de6a725b04f9005fa53fab240edb3d2c576a6c97 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 02:46:37 -0500 Subject: [PATCH 0432/1454] Fix G2/G3 segment size Fixes #17348 --- Marlin/src/gcode/motion/G2_G3.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 1e8365d6d2..0352947cca 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -112,8 +112,13 @@ void plan_arc( #else constexpr float seg_length = MM_PER_ARC_SEGMENT; #endif + + // Length divided by segment size gives segment count uint16_t segments = FLOOR(mm_of_travel / seg_length); - NOLESS(segments, min_segments); + if (segments < min_segments) { + segments = min_segments; // No fewer than the minimum + seg_length = mm_of_travel / segments; // A new segment length + } /** * Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, From 8d3caa9944da8990b07494974fe0ab710c321dd1 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 10 May 2020 01:08:01 -0700 Subject: [PATCH 0433/1454] Newer TMCStepper better for LPC176x (#17934) --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 99d1a46303..aca4b55297 100644 --- a/platformio.ini +++ b/platformio.ini @@ -266,7 +266,7 @@ src_filter = ${common.default_src_filter} + lib_deps = Servo LiquidCrystal U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip - TMCStepper@>=0.6.1,<1.0.0 + TMCStepper@>=0.6.2 Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip @@ -284,7 +284,7 @@ src_filter = ${common.default_src_filter} + lib_deps = Servo LiquidCrystal U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip - TMCStepper@>=0.6.1,<1.0.0 + TMCStepper@>=0.6.2 Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip From 32dc874928bf78b9192bc1a790b9151a9f6cf3c5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 03:42:48 -0500 Subject: [PATCH 0434/1454] Tempted by the const of a seg_length --- Marlin/src/gcode/motion/G2_G3.cpp | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 0352947cca..91923121c5 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -103,21 +103,21 @@ void plan_arc( const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); - #ifdef ARC_SEGMENTS_PER_R - float seg_length = MM_PER_ARC_SEGMENT * radius; - LIMIT(seg_length, MM_PER_ARC_SEGMENT, ARC_SEGMENTS_PER_R); - #elif ARC_SEGMENTS_PER_SEC - float seg_length = scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC); - NOLESS(seg_length, MM_PER_ARC_SEGMENT); - #else - constexpr float seg_length = MM_PER_ARC_SEGMENT; - #endif - - // Length divided by segment size gives segment count + // Start with a nominal segment length + float seg_length = ( + #ifdef ARC_SEGMENTS_PER_R + constrain(MM_PER_ARC_SEGMENT * radius, MM_PER_ARC_SEGMENT, ARC_SEGMENTS_PER_R) + #elif ARC_SEGMENTS_PER_SEC + _MAX(scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC), MM_PER_ARC_SEGMENT) + #else + MM_PER_ARC_SEGMENT + #endif + ); + // Divide total travel by nominal segment length uint16_t segments = FLOOR(mm_of_travel / seg_length); - if (segments < min_segments) { - segments = min_segments; // No fewer than the minimum - seg_length = mm_of_travel / segments; // A new segment length + if (segments < min_segments) { // Too few segments? + segments = min_segments; // More segments + seg_length = mm_of_travel / segments; // but also shorter } /** From e5b0892f08f605a99dc15d68a6fef4b8f85cbe72 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 04:40:19 -0500 Subject: [PATCH 0435/1454] Fix TERN typo, EXTRA_PROBING Co-Authored-By: Matthew Kennedy --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 ++-- Marlin/src/module/probe.cpp | 15 +++++++++------ 3 files changed, 12 insertions(+), 9 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 3ea27be420..2ab3f426e2 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -605,7 +605,7 @@ #define PROBE_TRIGGERED_WHEN_STOWED_TEST 1 // Extra test for Allen Key Probe #endif #if MULTIPLE_PROBING > 1 - #if EXTRA_PROBING + #if EXTRA_PROBING > 0 #define TOTAL_PROBING (MULTIPLE_PROBING + EXTRA_PROBING) #else #define TOTAL_PROBING MULTIPLE_PROBING diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c420740125..11cc7060d4 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1285,8 +1285,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Probes need Z_AFTER_PROBING >= 0." #endif - #if MULTIPLE_PROBING || EXTRA_PROBING - #if !MULTIPLE_PROBING + #if MULTIPLE_PROBING > 0 || EXTRA_PROBING > 0 + #if MULTIPLE_PROBING == 0 #error "EXTRA_PROBING requires MULTIPLE_PROBING." #elif MULTIPLE_PROBING < 2 #error "MULTIPLE_PROBING must be 2 or more." diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index d08ba27e1b..6aefcfa8ac 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -565,14 +565,14 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { } #endif - #ifdef EXTRA_PROBING + #if EXTRA_PROBING > 0 float probes[TOTAL_PROBING]; #endif #if TOTAL_PROBING > 2 float probes_z_sum = 0; for ( - #if EXTRA_PROBING + #if EXTRA_PROBING > 0 uint8_t p = 0; p < TOTAL_PROBING; p++ #else uint8_t p = TOTAL_PROBING; p--; @@ -588,7 +588,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { const float z = current_position.z; - #if EXTRA_PROBING + #if EXTRA_PROBING > 0 // Insert Z measurement into probes[]. Keep it sorted ascending. LOOP_LE_N(i, p) { // Iterate the saved Zs to insert the new Z if (i == p || probes[i] > z) { // Last index or new Z is smaller than this Z @@ -605,14 +605,17 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #if TOTAL_PROBING > 2 // Small Z raise after all but the last probe - if (TERN(EXTRA_PROBING, p < TOTAL_PROBING - 1, p)) - do_blocking_move_to_z(z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + if (p + #if EXTRA_PROBING > 0 + < TOTAL_PROBING - 1 + #endif + ) do_blocking_move_to_z(z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); #endif } #if TOTAL_PROBING > 2 - #if EXTRA_PROBING + #if EXTRA_PROBING > 0 // Take the center value (or average the two middle values) as the median static constexpr int PHALF = (TOTAL_PROBING - 1) / 2; const float middle = probes[PHALF], From 86c112538084f7718252966f5f9d9278c4837fb2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 04:52:51 -0500 Subject: [PATCH 0436/1454] Sanity check 3-point defines Fixes #17870 --- Marlin/src/inc/Conditionals_post.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 26cad87979..fe8778590a 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2338,9 +2338,13 @@ #undef MESH_MAX_Y #endif -#if defined(PROBE_PT_1_X) && defined(PROBE_PT_2_X) && defined(PROBE_PT_3_X) && defined(PROBE_PT_1_Y) && defined(PROBE_PT_2_Y) && defined(PROBE_PT_3_Y) +#define _POINT_COUNT (defined(PROBE_PT_1_X) + defined(PROBE_PT_2_X) + defined(PROBE_PT_3_X) + defined(PROBE_PT_1_Y) + defined(PROBE_PT_2_Y) + defined(PROBE_PT_3_Y)) +#if _POINT_COUNT == 6 #define HAS_FIXED_3POINT 1 +#elif _POINT_COUNT > 0 + #error "For 3-Point Leveling all XY points must be defined (or none for the defaults)." #endif +#undef _POINT_COUNT /** * Buzzer/Speaker From 33127f4476dcce07c380fae5f2b708f73de2fc87 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 18:42:42 -0500 Subject: [PATCH 0437/1454] More conservative Trinamic DIR delay See #17323 This makes babystepping more reliable and may improve Trinamic motion overall. Co-Authored-By: chgi --- Marlin/src/inc/Conditionals_adv.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 2dd9f95d81..2009e7c965 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -259,11 +259,10 @@ #endif /** - * Driver Timings + * Driver Timings (in nanoseconds) * NOTE: Driver timing order is longest-to-shortest duration. * Preserve this ordering when adding new drivers. */ - #ifndef MINIMUM_STEPPER_POST_DIR_DELAY #if HAS_DRIVER(TB6560) #define MINIMUM_STEPPER_POST_DIR_DELAY 15000 @@ -278,7 +277,7 @@ #elif HAS_DRIVER(A4988) #define MINIMUM_STEPPER_POST_DIR_DELAY 200 #elif HAS_TRINAMIC_CONFIG || HAS_TRINAMIC_STANDALONE - #define MINIMUM_STEPPER_POST_DIR_DELAY 20 + #define MINIMUM_STEPPER_POST_DIR_DELAY 60 #else #define MINIMUM_STEPPER_POST_DIR_DELAY 0 // Expect at least 10µS since one Stepper ISR must transpire #endif From df7250baa84de986c3351e7c9ca61617efea36c8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 11 May 2020 00:04:00 +0000 Subject: [PATCH 0438/1454] [cron] Bump distribution date (2020-05-11) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 88c579aee3..83be7f72e6 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-10" + #define STRING_DISTRIBUTION_DATE "2020-05-11" #endif /** From 3b87fc19e4ab1182d22b83197cb75a470f3123be Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 10 May 2020 19:28:49 -0500 Subject: [PATCH 0439/1454] Adjust some variants spacing, comments --- .../variants/BIGTREE_BTT002/PeripheralPins.c | 12 +++- .../variants/BIGTREE_BTT002/PinNamesVar.h | 38 ++++++------ .../BIGTREE_SKR_PRO_1v1/PeripheralPins.c | 4 +- .../BIGTREE_SKR_PRO_1v1/PinNamesVar.h | 38 ++++++------ .../variants/FLY_F407ZG/PinNamesVar.h | 60 +++++++++---------- .../variants/FYSETC_S6/PinNamesVar.h | 20 +++---- .../variants/MARLIN_F407VE/PinNamesVar.h | 60 +++++++++---------- .../variants/STEVAL_F401VE/PinNamesVar.h | 26 ++++---- 8 files changed, 132 insertions(+), 126 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c index 7f5ca78356..cff269db0b 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c @@ -123,12 +123,18 @@ const PinMap PinMap_PWM[] = { {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 - //probably unused on SKR-Pro. confirmation needed, please. + /** + * Unused by specifications on BTT002. (PLEASE CONFIRM) + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 is bltouch analog? + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 is bltouch analog? + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PinNamesVar.h b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PinNamesVar.h index 2424885937..b4bb9d45f8 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PinNamesVar.h @@ -25,25 +25,25 @@ #endif /* USB */ #ifdef USBCON - USB_OTG_FS_SOF = PA_8, - USB_OTG_FS_VBUS = PA_9, - USB_OTG_FS_ID = PA_10, - USB_OTG_FS_DM = PA_11, - USB_OTG_FS_DP = PA_12, - USB_OTG_HS_ULPI_D0 = PA_3, - USB_OTG_HS_SOF = PA_4, - USB_OTG_HS_ULPI_CK = PA_5, - USB_OTG_HS_ULPI_D1 = PB_0, - USB_OTG_HS_ULPI_D2 = PB_1, - USB_OTG_HS_ULPI_D7 = PB_5, - USB_OTG_HS_ULPI_D3 = PB_10, - USB_OTG_HS_ULPI_D4 = PB_11, - USB_OTG_HS_ID = PB_12, - USB_OTG_HS_ULPI_D5 = PB_12, - USB_OTG_HS_ULPI_D6 = PB_13, - USB_OTG_HS_VBUS = PB_13, - USB_OTG_HS_DM = PB_14, - USB_OTG_HS_DP = PB_15, + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, USB_OTG_HS_ULPI_STP = PC_0, USB_OTG_HS_ULPI_DIR = PC_2, USB_OTG_HS_ULPI_NXT = PC_3, diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c index a772f64fb7..a28e712e0d 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c @@ -152,8 +152,8 @@ const PinMap PinMap_PWM[] = { */ //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 is bltouch analog? - {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 is bltouch analog? + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h index 2424885937..b4bb9d45f8 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h @@ -25,25 +25,25 @@ #endif /* USB */ #ifdef USBCON - USB_OTG_FS_SOF = PA_8, - USB_OTG_FS_VBUS = PA_9, - USB_OTG_FS_ID = PA_10, - USB_OTG_FS_DM = PA_11, - USB_OTG_FS_DP = PA_12, - USB_OTG_HS_ULPI_D0 = PA_3, - USB_OTG_HS_SOF = PA_4, - USB_OTG_HS_ULPI_CK = PA_5, - USB_OTG_HS_ULPI_D1 = PB_0, - USB_OTG_HS_ULPI_D2 = PB_1, - USB_OTG_HS_ULPI_D7 = PB_5, - USB_OTG_HS_ULPI_D3 = PB_10, - USB_OTG_HS_ULPI_D4 = PB_11, - USB_OTG_HS_ID = PB_12, - USB_OTG_HS_ULPI_D5 = PB_12, - USB_OTG_HS_ULPI_D6 = PB_13, - USB_OTG_HS_VBUS = PB_13, - USB_OTG_HS_DM = PB_14, - USB_OTG_HS_DP = PB_15, + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, USB_OTG_HS_ULPI_STP = PC_0, USB_OTG_HS_ULPI_DIR = PC_2, USB_OTG_HS_ULPI_NXT = PC_3, diff --git a/buildroot/share/PlatformIO/variants/FLY_F407ZG/PinNamesVar.h b/buildroot/share/PlatformIO/variants/FLY_F407ZG/PinNamesVar.h index f3c4f0ee07..b4bb9d45f8 100644 --- a/buildroot/share/PlatformIO/variants/FLY_F407ZG/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/FLY_F407ZG/PinNamesVar.h @@ -1,50 +1,50 @@ /* SYS_WKUP */ #ifdef PWR_WAKEUP_PIN1 -SYS_WKUP1 = PA_0, + SYS_WKUP1 = PA_0, #endif #ifdef PWR_WAKEUP_PIN2 -SYS_WKUP2 = NC, + SYS_WKUP2 = NC, #endif #ifdef PWR_WAKEUP_PIN3 -SYS_WKUP3 = NC, + SYS_WKUP3 = NC, #endif #ifdef PWR_WAKEUP_PIN4 -SYS_WKUP4 = NC, + SYS_WKUP4 = NC, #endif #ifdef PWR_WAKEUP_PIN5 -SYS_WKUP5 = NC, + SYS_WKUP5 = NC, #endif #ifdef PWR_WAKEUP_PIN6 -SYS_WKUP6 = NC, + SYS_WKUP6 = NC, #endif #ifdef PWR_WAKEUP_PIN7 -SYS_WKUP7 = NC, + SYS_WKUP7 = NC, #endif #ifdef PWR_WAKEUP_PIN8 -SYS_WKUP8 = NC, + SYS_WKUP8 = NC, #endif /* USB */ #ifdef USBCON -USB_OTG_FS_SOF = PA_8, -USB_OTG_FS_VBUS = PA_9, -USB_OTG_FS_ID = PA_10, -USB_OTG_FS_DM = PA_11, -USB_OTG_FS_DP = PA_12, -USB_OTG_HS_ULPI_D0 = PA_3, -USB_OTG_HS_SOF = PA_4, -USB_OTG_HS_ULPI_CK = PA_5, -USB_OTG_HS_ULPI_D1 = PB_0, -USB_OTG_HS_ULPI_D2 = PB_1, -USB_OTG_HS_ULPI_D7 = PB_5, -USB_OTG_HS_ULPI_D3 = PB_10, -USB_OTG_HS_ULPI_D4 = PB_11, -USB_OTG_HS_ID = PB_12, -USB_OTG_HS_ULPI_D5 = PB_12, -USB_OTG_HS_ULPI_D6 = PB_13, -USB_OTG_HS_VBUS = PB_13, -USB_OTG_HS_DM = PB_14, -USB_OTG_HS_DP = PB_15, -USB_OTG_HS_ULPI_STP = PC_0, -USB_OTG_HS_ULPI_DIR = PC_2, -USB_OTG_HS_ULPI_NXT = PC_3, + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, #endif diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h b/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h index 77f1689b3d..bff3f21349 100644 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h @@ -1,30 +1,30 @@ /* SYS_WKUP */ #ifdef PWR_WAKEUP_PIN1 -SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ + SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ #endif #ifdef PWR_WAKEUP_PIN2 -SYS_WKUP2 = NC, + SYS_WKUP2 = NC, #endif #ifdef PWR_WAKEUP_PIN3 -SYS_WKUP3 = NC, + SYS_WKUP3 = NC, #endif #ifdef PWR_WAKEUP_PIN4 -SYS_WKUP4 = NC, + SYS_WKUP4 = NC, #endif #ifdef PWR_WAKEUP_PIN5 -SYS_WKUP5 = NC, + SYS_WKUP5 = NC, #endif #ifdef PWR_WAKEUP_PIN6 -SYS_WKUP6 = NC, + SYS_WKUP6 = NC, #endif #ifdef PWR_WAKEUP_PIN7 -SYS_WKUP7 = NC, + SYS_WKUP7 = NC, #endif #ifdef PWR_WAKEUP_PIN8 -SYS_WKUP8 = NC, + SYS_WKUP8 = NC, #endif /* USB */ #ifdef USBCON -USB_OTG_FS_DM = PA_11, -USB_OTG_FS_DP = PA_12, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, #endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/PinNamesVar.h index f3c4f0ee07..b4bb9d45f8 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/PinNamesVar.h @@ -1,50 +1,50 @@ /* SYS_WKUP */ #ifdef PWR_WAKEUP_PIN1 -SYS_WKUP1 = PA_0, + SYS_WKUP1 = PA_0, #endif #ifdef PWR_WAKEUP_PIN2 -SYS_WKUP2 = NC, + SYS_WKUP2 = NC, #endif #ifdef PWR_WAKEUP_PIN3 -SYS_WKUP3 = NC, + SYS_WKUP3 = NC, #endif #ifdef PWR_WAKEUP_PIN4 -SYS_WKUP4 = NC, + SYS_WKUP4 = NC, #endif #ifdef PWR_WAKEUP_PIN5 -SYS_WKUP5 = NC, + SYS_WKUP5 = NC, #endif #ifdef PWR_WAKEUP_PIN6 -SYS_WKUP6 = NC, + SYS_WKUP6 = NC, #endif #ifdef PWR_WAKEUP_PIN7 -SYS_WKUP7 = NC, + SYS_WKUP7 = NC, #endif #ifdef PWR_WAKEUP_PIN8 -SYS_WKUP8 = NC, + SYS_WKUP8 = NC, #endif /* USB */ #ifdef USBCON -USB_OTG_FS_SOF = PA_8, -USB_OTG_FS_VBUS = PA_9, -USB_OTG_FS_ID = PA_10, -USB_OTG_FS_DM = PA_11, -USB_OTG_FS_DP = PA_12, -USB_OTG_HS_ULPI_D0 = PA_3, -USB_OTG_HS_SOF = PA_4, -USB_OTG_HS_ULPI_CK = PA_5, -USB_OTG_HS_ULPI_D1 = PB_0, -USB_OTG_HS_ULPI_D2 = PB_1, -USB_OTG_HS_ULPI_D7 = PB_5, -USB_OTG_HS_ULPI_D3 = PB_10, -USB_OTG_HS_ULPI_D4 = PB_11, -USB_OTG_HS_ID = PB_12, -USB_OTG_HS_ULPI_D5 = PB_12, -USB_OTG_HS_ULPI_D6 = PB_13, -USB_OTG_HS_VBUS = PB_13, -USB_OTG_HS_DM = PB_14, -USB_OTG_HS_DP = PB_15, -USB_OTG_HS_ULPI_STP = PC_0, -USB_OTG_HS_ULPI_DIR = PC_2, -USB_OTG_HS_ULPI_NXT = PC_3, + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, #endif diff --git a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PinNamesVar.h index 3082f8842a..6a1eb9b887 100644 --- a/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/STEVAL_F401VE/PinNamesVar.h @@ -1,33 +1,33 @@ /* SYS_WKUP */ #ifdef PWR_WAKEUP_PIN1 -SYS_WKUP1 = PA_0, + SYS_WKUP1 = PA_0, #endif #ifdef PWR_WAKEUP_PIN2 -SYS_WKUP2 = NC, + SYS_WKUP2 = NC, #endif #ifdef PWR_WAKEUP_PIN3 -SYS_WKUP3 = NC, + SYS_WKUP3 = NC, #endif #ifdef PWR_WAKEUP_PIN4 -SYS_WKUP4 = NC, + SYS_WKUP4 = NC, #endif #ifdef PWR_WAKEUP_PIN5 -SYS_WKUP5 = NC, + SYS_WKUP5 = NC, #endif #ifdef PWR_WAKEUP_PIN6 -SYS_WKUP6 = NC, + SYS_WKUP6 = NC, #endif #ifdef PWR_WAKEUP_PIN7 -SYS_WKUP7 = NC, + SYS_WKUP7 = NC, #endif #ifdef PWR_WAKEUP_PIN8 -SYS_WKUP8 = NC, + SYS_WKUP8 = NC, #endif /* USB */ #ifdef USBCON -USB_OTG_FS_SOF = PA_8, -USB_OTG_FS_VBUS = PA_9, -USB_OTG_FS_ID = PA_10, -USB_OTG_FS_DM = PA_11, -USB_OTG_FS_DP = PA_12, + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, #endif From 00e7599c8caaf9d76024bcb000df169bfe3bfe8a Mon Sep 17 00:00:00 2001 From: Desuuuu Date: Mon, 11 May 2020 02:19:23 +0000 Subject: [PATCH 0440/1454] Fix host_action_notify and string types (#17953) --- Marlin/src/feature/host_actions.cpp | 20 +++++++++++++------- Marlin/src/feature/host_actions.h | 13 +++++++------ Marlin/src/lcd/ultralcd.cpp | 6 +++--- 3 files changed, 23 insertions(+), 16 deletions(-) diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index d33ff09498..e85c5bf623 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -37,7 +37,7 @@ #include "runout.h" #endif -void host_action(const char * const pstr, const bool eol) { +void host_action(PGM_P const pstr, const bool eol) { SERIAL_ECHOPGM("//action:"); serialprintPGM(pstr); if (eol) SERIAL_EOL(); @@ -74,33 +74,39 @@ void host_action(const char * const pstr, const bool eol) { PromptReason host_prompt_reason = PROMPT_NOT_DEFINED; void host_action_notify(const char * const message) { + host_action(PSTR("notification "), false); + SERIAL_ECHO(message); + SERIAL_EOL(); + } + + void host_action_notify_P(PGM_P const message) { host_action(PSTR("notification "), false); serialprintPGM(message); SERIAL_EOL(); } - void host_action_prompt(const char * const ptype, const bool eol=true) { + void host_action_prompt(PGM_P const ptype, const bool eol=true) { host_action(PSTR("prompt_"), false); serialprintPGM(ptype); if (eol) SERIAL_EOL(); } - void host_action_prompt_plus(const char * const ptype, const char * const pstr, const char extra_char='\0') { + void host_action_prompt_plus(PGM_P const ptype, PGM_P const pstr, const char extra_char='\0') { host_action_prompt(ptype, false); SERIAL_CHAR(' '); serialprintPGM(pstr); if (extra_char != '\0') SERIAL_CHAR(extra_char); SERIAL_EOL(); } - void host_action_prompt_begin(const PromptReason reason, const char * const pstr, const char extra_char/*='\0'*/) { + void host_action_prompt_begin(const PromptReason reason, PGM_P const pstr, const char extra_char/*='\0'*/) { host_action_prompt_end(); host_prompt_reason = reason; host_action_prompt_plus(PSTR("begin"), pstr, extra_char); } - void host_action_prompt_button(const char * const pstr) { host_action_prompt_plus(PSTR("button"), pstr); } + void host_action_prompt_button(PGM_P const pstr) { host_action_prompt_plus(PSTR("button"), pstr); } void host_action_prompt_end() { host_action_prompt(PSTR("end")); } void host_action_prompt_show() { host_action_prompt(PSTR("show")); } - void host_prompt_do(const PromptReason reason, const char * const pstr, const char * const btn1/*=nullptr*/, const char * const btn2/*=nullptr*/) { + void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { host_action_prompt_begin(reason, pstr); if (btn1) host_action_prompt_button(btn1); if (btn2) host_action_prompt_button(btn2); @@ -127,7 +133,7 @@ void host_action(const char * const pstr, const bool eol) { serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("ason: ", host_prompt_reason); serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("sponse: ", response); #endif - const char *msg = PSTR("UNKNOWN STATE"); + PGM_P msg = PSTR("UNKNOWN STATE"); const PromptReason hpr = host_prompt_reason; host_prompt_reason = PROMPT_NOT_DEFINED; // Reset now ahead of logic switch (hpr) { diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 3667b7f430..07309274b0 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -21,9 +21,9 @@ */ #pragma once -#include "../inc/MarlinConfigPre.h" +#include "../inc/MarlinConfig.h" -void host_action(const char * const pstr, const bool eol=true); +void host_action(PGM_P const pstr, const bool eol=true); #ifdef ACTION_ON_KILL void host_action_kill(); @@ -61,12 +61,13 @@ void host_action(const char * const pstr, const bool eol=true); void host_response_handler(const uint8_t response); void host_action_notify(const char * const message); - void host_action_prompt_begin(const PromptReason reason, const char * const pstr, const char extra_char='\0'); - void host_action_prompt_button(const char * const pstr); + void host_action_notify_P(PGM_P const message); + void host_action_prompt_begin(const PromptReason reason, PGM_P const pstr, const char extra_char='\0'); + void host_action_prompt_button(PGM_P const pstr); void host_action_prompt_end(); void host_action_prompt_show(); - void host_prompt_do(const PromptReason reason, const char * const pstr, const char * const btn1=nullptr, const char * const btn2=nullptr); - inline void host_prompt_open(const PromptReason reason, const char * const pstr, const char * const btn1=nullptr, const char * const btn2=nullptr) { + void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr); + inline void host_prompt_open(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr) { if (host_prompt_reason == PROMPT_NOT_DEFINED) host_prompt_do(reason, pstr, btn1, btn2); } diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 5ed529df76..76aa773cd3 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1303,7 +1303,7 @@ void MarlinUI::update() { if (level < alert_level) return; alert_level = level; - TERN_(HOST_PROMPT_SUPPORT, host_action_notify(message)); + TERN_(HOST_PROMPT_SUPPORT, host_action_notify_P(message)); // Since the message is encoded in UTF8 it must // only be cut on a character boundary. @@ -1450,10 +1450,10 @@ void MarlinUI::update() { TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); } void MarlinUI::set_status_P(PGM_P message, const int8_t) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); + TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); } void MarlinUI::status_printf_P(const uint8_t, PGM_P const message, ...) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); + TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); } #endif // !HAS_DISPLAY From fcd1678a17e8fce115584613e14e80a56276bb50 Mon Sep 17 00:00:00 2001 From: Desuuuu Date: Mon, 11 May 2020 02:21:47 +0000 Subject: [PATCH 0441/1454] Actually apply DGUS_[RT]X_BUFFER_SIZE (#17952) --- Marlin/src/HAL/AVR/MarlinSerial.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index e39ebc4037..fc20a48ec5 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -299,8 +299,8 @@ template struct MarlinInternalSerialCfg { static constexpr int PORT = serial; - static constexpr unsigned int RX_SIZE = 128; - static constexpr unsigned int TX_SIZE = 48; + static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE; + static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE; static constexpr bool XONOFF = false; static constexpr bool EMERGENCYPARSER = false; static constexpr bool DROPPED_RX = false; From e22e0763d94a94776a33f8557dddadc3432342cf Mon Sep 17 00:00:00 2001 From: XDA-Bam <1209896+XDA-Bam@users.noreply.github.com> Date: Mon, 11 May 2020 04:23:51 +0200 Subject: [PATCH 0442/1454] Reduce division in JD calc (#17945) --- Marlin/src/module/planner.h | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index f2b90cd994..60dbb612c7 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -910,8 +910,12 @@ class Planner { FORCE_INLINE static float limit_value_by_axis_maximum(const float &max_value, xyze_float_t &unit_vec) { float limit_value = max_value; - LOOP_XYZE(idx) if (unit_vec[idx]) // Avoid divide by zero - NOMORE(limit_value, ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx])); + LOOP_XYZE(idx) { + if (unit_vec[idx]) { + if (limit_value * ABS(unit_vec[idx]) > settings.max_acceleration_mm_per_s2[idx]) + limit_value = ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx]); + } + } return limit_value; } From 3381a4ab0322af75124e920e61840c7a753ffadf Mon Sep 17 00:00:00 2001 From: XDA-Bam <1209896+XDA-Bam@users.noreply.github.com> Date: Mon, 11 May 2020 08:06:35 +0200 Subject: [PATCH 0443/1454] Fix vector normalization in JD (#17938) --- Marlin/src/module/planner.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 9c1071c6fb..7d23789df1 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2256,16 +2256,17 @@ bool Planner::_populate_block(block_t * const block, bool split_move, { steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.e } #endif ; - unit_vec *= inverse_millimeters; - #if IS_CORE && HAS_JUNCTION_DEVIATION - /** - * On CoreXY the length of the vector [A,B] is SQRT(2) times the length of the head movement vector [X,Y]. - * So taking Z and E into account, we cannot scale to a unit vector with "inverse_millimeters". - * => normalize the complete junction vector - */ - normalize_junction_vector(unit_vec); - #endif + /** + * On CoreXY the length of the vector [A,B] is SQRT(2) times the length of the head movement vector [X,Y]. + * So taking Z and E into account, we cannot scale to a unit vector with "inverse_millimeters". + * => normalize the complete junction vector. + * Elsewise, when needed JD factors in the E component + */ + if (ENABLED(IS_CORE) || esteps > 0) + normalize_junction_vector(unit_vec); // Normalize with XYZE components + else + unit_vec *= inverse_millimeters; // Use pre-calculated (1 / SQRT(x^2 + y^2 + z^2)) // Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles. if (moves_queued && !UNEAR_ZERO(previous_nominal_speed_sqr)) { From 9d545f1231cd8405dce65eba04c461e205f814b7 Mon Sep 17 00:00:00 2001 From: Eric Ptak Date: Mon, 11 May 2020 08:07:19 +0200 Subject: [PATCH 0444/1454] Fysetc S6 direct DFU upload (#17943) --- .../PlatformIO/scripts/fysetc_STM32S6.py | 22 ------------------- platformio.ini | 4 ++-- 2 files changed, 2 insertions(+), 24 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py b/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py index be010b10fe..f6598ede65 100644 --- a/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py +++ b/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py @@ -31,25 +31,3 @@ for file_name in os.listdir(source_dir): full_file_name = os.path.join(source_dir, file_name) if os.path.isfile(full_file_name): shutil.copy(full_file_name, variant_dir) - -# Relocate firmware from 0x08000000 to 0x08002000 -#env['CPPDEFINES'].remove(("VECT_TAB_ADDR", 134217728)) -#env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08010000")) -#env.Replace(LDSCRIPT_PATH="buildroot/share/PlatformIO/ldscripts/fysetc_aio_ii.ld") - -# Custom HEX from ELF -env.AddPostAction( - "$BUILD_DIR/${PROGNAME}.elf", - env.VerboseAction(" ".join([ - "$OBJCOPY", - "-O", - "ihex", - "$BUILD_DIR/${PROGNAME}.elf", - "$BUILD_DIR/${PROGNAME}.hex" - ]), "Building $TARGET")) - -# In-line command with arguments -env.Replace( - UPLOADER=platform.get_package_dir("tool-stm32duino") + '/stm32flash/stm32flash', - UPLOADCMD='"${UPLOADER}" -v -i rts,-dtr,dtr,-rts -R -b 115200 -g 0x8000000 -w "${BUILD_DIR}/${PROGNAME}.hex" ${UPLOAD_PORT}' -) diff --git a/platformio.ini b/platformio.ini index aca4b55297..81855b3030 100644 --- a/platformio.ini +++ b/platformio.ini @@ -729,8 +729,8 @@ extra_scripts = pre:buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py src_filter = ${common.default_src_filter} + lib_ignore = Arduino-L6470, SoftwareSerial debug_tool = stlink -#upload_protocol = stlink -upload_protocol = serial +upload_protocol = dfu +upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" # # STM32F407VET6 with RAMPS-like shield From 25aade1cf13d6d8936859328addf21307b63d91e Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 10 May 2020 23:10:20 -0700 Subject: [PATCH 0445/1454] Improve STM32F4 Flash Behavior (#17946) --- Marlin/src/HAL/STM32/Servo.cpp | 42 ++++++++++++++++++++++---- Marlin/src/HAL/STM32/Servo.h | 18 +++++++++-- Marlin/src/HAL/STM32/eeprom_flash.cpp | 31 ++++++++++++++++--- Marlin/src/HAL/STM32/inc/SanityCheck.h | 9 ++++++ 4 files changed, 87 insertions(+), 13 deletions(-) diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index d192da5d28..5fb8e3cd6a 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -29,32 +29,62 @@ #include "Servo.h" static uint_fast8_t servoCount = 0; +static libServo *servos[NUM_SERVOS] = {0}; constexpr millis_t servoDelay[] = SERVO_DELAY; static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); libServo::libServo() -: delay(servoDelay[servoCount++]) -{} +: delay(servoDelay[servoCount]), + was_attached_before_pause(false), + value_before_pause(0) +{ + servos[servoCount++] = this; +} int8_t libServo::attach(const int pin) { if (servoCount >= MAX_SERVOS) return -1; if (pin > 0) servo_pin = pin; - return super::attach(servo_pin); + return stm32_servo.attach(servo_pin); } int8_t libServo::attach(const int pin, const int min, const int max) { if (servoCount >= MAX_SERVOS) return -1; if (pin > 0) servo_pin = pin; - return super::attach(servo_pin, min, max); + return stm32_servo.attach(servo_pin, min, max); } void libServo::move(const int value) { if (attach(0) >= 0) { - write(value); + stm32_servo.write(value); safe_delay(delay); TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } } -#endif // HAS_SERVOS +void libServo::pause() { + was_attached_before_pause = stm32_servo.attached(); + if (was_attached_before_pause) { + value_before_pause = stm32_servo.read(); + stm32_servo.detach(); + } +} + +void libServo::resume() { + if (was_attached_before_pause) { + attach(); + move(value_before_pause); + } +} + +void libServo::pause_all_servos() { + for (auto& servo : servos) + if (servo) servo->pause(); +} + +void libServo::resume_all_servos() { + for (auto& servo : servos) + if (servo) servo->resume(); +} + +#endif // HAS_SERVOS #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h index e8b3c4b100..50ae1a9b94 100644 --- a/Marlin/src/HAL/STM32/Servo.h +++ b/Marlin/src/HAL/STM32/Servo.h @@ -27,15 +27,27 @@ #include "../../core/millis_t.h" // Inherit and expand on the official library -class libServo : public Servo { +class libServo { public: libServo(); - int8_t attach(const int pin); + int8_t attach(const int pin = 0); // pin == 0 uses value from previous call int8_t attach(const int pin, const int min, const int max); + void detach() { stm32_servo.detach(); } + int read() { return stm32_servo.read(); } void move(const int value); + + void pause(); + void resume(); + + static void pause_all_servos(); + static void resume_all_servos(); + private: - typedef Servo super; + Servo stm32_servo; int servo_pin = 0; millis_t delay = 0; + + bool was_attached_before_pause; + int value_before_pause; }; diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 49862957e8..309c5eea9f 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -28,10 +28,13 @@ #include "../shared/eeprom_api.h" - -// Only STM32F4 can support wear leveling at this time -#ifndef STM32F4xx - #undef FLASH_EEPROM_LEVELING +#if HAS_SERVOS + #include "Servo.h" + #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() + #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() +#else + #define PAUSE_SERVO_OUTPUT() + #define RESUME_SERVO_OUTPUT() #endif /** @@ -139,6 +142,11 @@ bool PersistentStore::access_start() { bool PersistentStore::access_finish() { if (eeprom_data_written) { + #ifdef STM32F4xx + // MCU may come up with flash error bits which prevent some flash operations. + // Clear flags prior to flash operations to prevent errors. + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); + #endif #if ENABLED(FLASH_EEPROM_LEVELING) @@ -159,7 +167,11 @@ bool PersistentStore::access_finish() { current_slot = EEPROM_SLOTS - 1; UNLOCK_FLASH(); + PAUSE_SERVO_OUTPUT(); + DISABLE_ISRS(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); + ENABLE_ISRS(); + RESUME_SERVO_OUTPUT(); if (status != HAL_OK) { DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status); DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError()); @@ -204,7 +216,18 @@ bool PersistentStore::access_finish() { return success; #else + // The following was written for the STM32F4 but may work with other MCUs as well. + // Most STM32F4 flash does not allow reading from flash during erase operations. + // This takes about a second on a STM32F407 with a 128kB sector used as EEPROM. + // Interrupts during this time can have unpredictable results, such as killing Servo + // output. Servo output still glitches with interrupts disabled, but recovers after the + // erase. + PAUSE_SERVO_OUTPUT(); + DISABLE_ISRS(); eeprom_buffer_flush(); + ENABLE_ISRS(); + RESUME_SERVO_OUTPUT(); + eeprom_data_written = false; #endif } diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 9cd8db81f4..7734fc0e83 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -43,3 +43,12 @@ #endif #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." #endif + +#if defined(STM32F4xx) && BOTH(PRINTCOUNTER, FLASH_EEPROM_EMULATION) + #warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing." + #error "Disable PRINTCOUNTER or choose another EEPROM emulation." +#endif + +#if !defined(STM32F4xx) && ENABLED(FLASH_EEPROM_LEVELING) + #error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4 hardware." +#endif From 4680aa659cc9deef619faf2b0a58f2a626c28e0c Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 10 May 2020 23:12:11 -0700 Subject: [PATCH 0446/1454] EEPROM Flash Leveling enabled for more STM32F4 (#17948) --- Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 6 ++++++ Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 6 ++++++ Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 6 ++++++ Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 ++ 4 files changed, 20 insertions(+) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 838a5e9447..ae4d611865 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -35,6 +35,12 @@ #define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation #endif +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#endif + // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index a61ef1afaf..ce3a282b5e 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -38,6 +38,12 @@ //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation #endif +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#endif + #define TP // Enable to define servo and probe pins // diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 8eadf523f3..3df81a7842 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -35,6 +35,12 @@ #define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation #endif +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#endif + // // Servos // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index e3f02bb73a..18a91d3ea0 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -47,6 +47,8 @@ #endif #if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. #define FLASH_EEPROM_LEVELING #elif ENABLED(I2C_EEPROM) #undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. From 1475fd312a1572e1d43978f669bce02a72f63dab Mon Sep 17 00:00:00 2001 From: chestwood96 Date: Mon, 11 May 2020 09:06:31 +0200 Subject: [PATCH 0447/1454] M600 R (#17919) Co-authored-by: Scott Lahteine --- Marlin/src/feature/pause.cpp | 34 +++++++++++++++++-------- Marlin/src/feature/pause.h | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 4 ++- 3 files changed, 27 insertions(+), 13 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index f3c57bc923..931ddb34a3 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -84,26 +84,30 @@ fil_change_settings_t fc_settings[EXTRUDERS]; #endif #if HAS_BUZZER - static void filament_change_beep(const int8_t max_beep_count, const bool init=false) { + static void impatient_beep(const int8_t max_beep_count, const bool restart=false) { if (TERN0(HAS_LCD_MENU, pause_mode == PAUSE_MODE_PAUSE_PRINT)) return; static millis_t next_buzz = 0; static int8_t runout_beep = 0; - if (init) next_buzz = runout_beep = 0; + if (restart) next_buzz = runout_beep = 0; + + const bool always = max_beep_count < 0; const millis_t ms = millis(); if (ELAPSED(ms, next_buzz)) { - if (max_beep_count < 0 || runout_beep < max_beep_count + 5) { // Only beep as long as we're supposed to - next_buzz = ms + ((max_beep_count < 0 || runout_beep < max_beep_count) ? 1000 : 500); + if (always || runout_beep < max_beep_count + 5) { // Only beep as long as we're supposed to + next_buzz = ms + ((always || runout_beep < max_beep_count) ? 1000 : 500); BUZZ(50, 880 - (runout_beep & 1) * 220); runout_beep++; } } } + inline void first_impatient_beep(const int8_t max_beep_count) { impatient_beep(max_beep_count, true); } #else - inline void filament_change_beep(const int8_t, const bool=false) {} + inline void impatient_beep(const int8_t, const bool=false) {} + inline void first_impatient_beep(const int8_t) {} #endif /** @@ -165,7 +169,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_INSERT)); - filament_change_beep(max_beep_count, true); + first_impatient_beep(max_beep_count); KEEPALIVE_STATE(PAUSED_FOR_USER); #if ENABLED(HOST_PROMPT_SUPPORT) @@ -180,7 +184,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); while (wait_for_user) { - filament_change_beep(max_beep_count); + impatient_beep(max_beep_count); idle_no_sleep(); } } @@ -448,7 +452,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep show_continue_prompt(is_reload); - filament_change_beep(max_beep_count, true); + first_impatient_beep(max_beep_count); // Start the heater idle timers const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); @@ -468,7 +472,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED))); wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { - filament_change_beep(max_beep_count); + impatient_beep(max_beep_count); // If the nozzle has timed out... if (!nozzle_timed_out) @@ -508,7 +512,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep wait_for_user = true; nozzle_timed_out = false; - filament_change_beep(max_beep_count, true); + first_impatient_beep(max_beep_count); } idle_no_sleep(); } @@ -539,7 +543,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep * - Send host action for resume, if configured * - Resume the current SD print job, if any */ -void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { +void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, int16_t targetTemp/*=0*/ DXC_ARGS) { /* SERIAL_ECHOLNPAIR( "start of resume_print()\ndual_x_carriage_mode:", dual_x_carriage_mode, @@ -558,9 +562,17 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le thermalManager.reset_hotend_idle_timer(e); } + if (targetTemp > thermalManager.degTargetHotend(active_extruder)) + thermalManager.setTargetHotend(targetTemp, active_extruder); + if (nozzle_timed_out || thermalManager.hotEnoughToExtrude(active_extruder)) // Load the new filament load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); + if (targetTemp > 0) { + thermalManager.setTargetHotend(targetTemp, active_extruder); + thermalManager.wait_for_hotend(active_extruder, false); + } + TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_RESUME)); // Retract to prevent oozing diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index a4d5a9ae83..18922e4242 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -87,7 +87,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); -void resume_print(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, const int8_t max_beep_count=0 DXC_PARAMS); +void resume_print(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, const int8_t max_beep_count=0, int16_t targetTemp=0 DXC_PARAMS); bool load_filament(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=0, const int8_t max_beep_count=0, const bool show_lcd=false, const bool pause_for_user=false, const PauseMode mode=PAUSE_MODE_PAUSE_PRINT DXC_PARAMS); diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index c22e32ceee..6c351daf79 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -56,6 +56,7 @@ * L[distance] - Extrude distance for insertion (manual reload) * B[count] - Number of times to beep, -1 for indefinite (if equipped with a buzzer) * T[toolhead] - Select extruder for filament change + * R[temp] - Resume temperature (in current units) * * Default values are used for omitted arguments. */ @@ -153,7 +154,8 @@ void GcodeSuite::M600() { resume_print(slow_load_length, fast_load_length, 0, beep_count DXC_PASS); #else wait_for_confirmation(true, beep_count DXC_PASS); - resume_print(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH, beep_count DXC_PASS); + resume_print(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH, + beep_count, (parser.seenval('R') ? parser.value_celsius() : 0) DXC_PASS); #endif } From 2f3077f2192981fa26659f990f37419c03c77159 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 11 May 2020 17:14:06 -0700 Subject: [PATCH 0448/1454] Tests (LPC176x): Emergency Parser (#17967) --- Marlin/Configuration_adv.h | 2 +- buildroot/share/tests/LPC1768-tests | 2 +- buildroot/share/tests/LPC1769-tests | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 25bd339169..8123582b80 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1784,7 +1784,7 @@ // Enable an emergency-command parser to intercept certain commands as they // enter the serial receive buffer, so they cannot be blocked. // Currently handles M108, M112, M410 -// Does not work on boards using AT90USB (USBCON) processors! +// Does not work on boards using AT90USB (USBCON), ESP32, STM32F1/4/7, or Teensy 3.5/3.6 processors! //#define EMERGENCY_PARSER // Bad Serial-connections can miss a received command by sending an 'ok' diff --git a/buildroot/share/tests/LPC1768-tests b/buildroot/share/tests/LPC1768-tests index 566cbd27a6..9daf919316 100755 --- a/buildroot/share/tests/LPC1768-tests +++ b/buildroot/share/tests/LPC1768-tests @@ -43,7 +43,7 @@ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT ADAPTIVE_FAN_ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA + LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER opt_set GRID_MAX_POINTS_X 16 opt_set NOZZLE_TO_PROBE_OFFSET "{ 0, 0, 0 }" exec_test $1 $2 "Re-ARM with NOZZLE_AS_PROBE and many features." diff --git a/buildroot/share/tests/LPC1769-tests b/buildroot/share/tests/LPC1769-tests index 1dda5ec417..53a7b28189 100755 --- a/buildroot/share/tests/LPC1769-tests +++ b/buildroot/share/tests/LPC1769-tests @@ -22,7 +22,7 @@ opt_enable VIKI2 SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA + LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER opt_set GRID_MAX_POINTS_X 16 exec_test $1 $2 "Smoothieboard with many features" From 174e41c17d0be1c969ca800358ee17aa2595f866 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 12 May 2020 00:19:12 +0000 Subject: [PATCH 0449/1454] [cron] Bump distribution date (2020-05-12) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 83be7f72e6..685fcbc25d 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-11" + #define STRING_DISTRIBUTION_DATE "2020-05-12" #endif /** From 8a22ef0c83a94f742be39005f259226e005ded2d Mon Sep 17 00:00:00 2001 From: Colin Godsey Date: Mon, 11 May 2020 18:22:41 -0600 Subject: [PATCH 0450/1454] G6 Direct Stepping (#17853) --- Marlin/Configuration_adv.h | 24 ++- Marlin/src/HAL/AVR/MarlinSerial.cpp | 24 ++- Marlin/src/MarlinCore.cpp | 11 + Marlin/src/feature/direct_stepping.cpp | 273 +++++++++++++++++++++++++ Marlin/src/feature/direct_stepping.h | 137 +++++++++++++ Marlin/src/gcode/gcode.cpp | 4 + Marlin/src/gcode/gcode.h | 2 + Marlin/src/gcode/geometry/G92.cpp | 4 +- Marlin/src/gcode/motion/G6.cpp | 61 ++++++ Marlin/src/inc/Conditionals_adv.h | 12 ++ Marlin/src/inc/SanityCheck.h | 9 + Marlin/src/lcd/language/language_en.h | 3 + Marlin/src/module/planner.cpp | 86 +++++++- Marlin/src/module/planner.h | 40 +++- Marlin/src/module/stepper.cpp | 213 ++++++++++++++++--- Marlin/src/module/stepper.h | 15 ++ buildroot/share/tests/mega2560-tests | 5 +- 17 files changed, 859 insertions(+), 64 deletions(-) create mode 100644 Marlin/src/feature/direct_stepping.cpp create mode 100644 Marlin/src/feature/direct_stepping.h create mode 100644 Marlin/src/gcode/motion/G6.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 8123582b80..0acb279fb6 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1663,6 +1663,16 @@ // Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. //#define BEZIER_CURVE_SUPPORT +/** + * Direct Stepping + * + * Comparable to the method used by Klipper, G6 direct stepping significantly + * reduces motion calculations, increases top printing speeds, and results in + * less step aliasing by calculating all motions in advance. + * Preparing your G-code: https://github.com/colinrgodsey/step-daemon + */ +//#define DIRECT_STEPPING + /** * G38 Probe Target * @@ -1731,14 +1741,16 @@ //================================= Buffers ================================= //=========================================================================== -// @section hidden +// @section motion -// The number of linear motions that can be in the plan at any give time. -// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering. -#if ENABLED(SDSUPPORT) - #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller +// The number of lineear moves that can be in the planner at once. +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32) +#if BOTH(SDSUPPORT, DIRECT_STEPPING) + #define BLOCK_BUFFER_SIZE 8 +#elif ENABLED(SDSUPPORT) + #define BLOCK_BUFFER_SIZE 16 #else - #define BLOCK_BUFFER_SIZE 16 // maximize block buffer + #define BLOCK_BUFFER_SIZE 16 #endif // @section serial diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 350d0f302d..c544b905f3 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -43,6 +43,10 @@ #include "MarlinSerial.h" #include "../../MarlinCore.h" + #if ENABLED(DIRECT_STEPPING) + #include "../../feature/direct_stepping.h" + #endif + template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } }; template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 }; template bool MarlinSerial::_written = false; @@ -131,6 +135,18 @@ static EmergencyParser::State emergency_state; // = EP_RESET + // This must read the R_UCSRA register before reading the received byte to detect error causes + if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes; + if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns; + if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors; + + // Read the character from the USART + uint8_t c = R_UDR; + + #if ENABLED(DIRECT_STEPPING) + if (page_manager.maybe_store_rxd_char(c)) return; + #endif + // Get the tail - Nothing can alter its value while this ISR is executing, but there's // a chance that this ISR interrupted the main process while it was updating the index. // The backup mechanism ensures the correct value is always returned. @@ -142,14 +158,6 @@ // Get the next element ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // This must read the R_UCSRA register before reading the received byte to detect error causes - if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes; - if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns; - if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors; - - // Read the character from the USART - uint8_t c = R_UDR; - if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c); // If the character is to be stored at the index just before the tail diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 73f936bc05..2434df0ad4 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -59,6 +59,10 @@ #include "gcode/parser.h" #include "gcode/queue.h" +#if ENABLED(DIRECT_STEPPING) + #include "feature/direct_stepping.h" +#endif + #if ENABLED(TOUCH_BUTTONS) #include "feature/touch/xpt2046.h" #endif @@ -713,6 +717,9 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { // Handle Joystick jogging TERN_(POLL_JOG, joystick.inject_jog_moves()); + + // Direct Stepping + TERN_(DIRECT_STEPPING, page_manager.write_responses()); } /** @@ -1124,6 +1131,10 @@ void setup() { SETUP_RUN(max7219.init()); #endif + #if ENABLED(DIRECT_STEPPING) + SETUP_RUN(page_manager.init()); + #endif + marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp new file mode 100644 index 0000000000..7bed075b87 --- /dev/null +++ b/Marlin/src/feature/direct_stepping.cpp @@ -0,0 +1,273 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(DIRECT_STEPPING) + +#include "direct_stepping.h" + +#include "../MarlinCore.h" + +#define CHECK_PAGE(I, R) do{ \ + if (I >= sizeof(page_states) / sizeof(page_states[0])) { \ + fatal_error = true; \ + return R; \ + } \ +}while(0) + +#define CHECK_PAGE_STATE(I, R, S) do { \ + CHECK_PAGE(I, R); \ + if (page_states[I] != S) { \ + fatal_error = true; \ + return R; \ + } \ +}while(0) + +namespace DirectStepping { + + template + State SerialPageManager::state; + + template + volatile bool SerialPageManager::fatal_error; + + template + volatile PageState SerialPageManager::page_states[Cfg::NUM_PAGES]; + + template + volatile bool SerialPageManager::page_states_dirty; + + template + millis_t SerialPageManager::next_response; + + template + uint8_t SerialPageManager::pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE]; + + template + uint8_t SerialPageManager::checksum; + + template + typename Cfg::write_byte_idx_t SerialPageManager::write_byte_idx; + + template + typename Cfg::page_idx_t SerialPageManager::write_page_idx; + + template + typename Cfg::write_byte_idx_t SerialPageManager::write_page_size; + + template + void SerialPageManager::init() { + for (int i = 0 ; i < Cfg::NUM_PAGES ; i++) + page_states[i] = PageState::FREE; + + fatal_error = false; + next_response = 0; + state = State::NEWLINE; + + page_states_dirty = false; + + SERIAL_ECHOLNPGM("pages_ready"); + } + + template + FORCE_INLINE bool SerialPageManager::maybe_store_rxd_char(uint8_t c) { + switch (state) { + default: + case State::MONITOR: + switch (c) { + case '\n': + case '\r': + state = State::NEWLINE; + default: + return false; + } + case State::NEWLINE: + switch (c) { + case Cfg::CONTROL_CHAR: + state = State::ADDRESS; + return true; + case '\n': + case '\r': + state = State::NEWLINE; + return false; + default: + state = State::MONITOR; + return false; + } + case State::ADDRESS: + //TODO: 16 bit address, State::ADDRESS2 + write_page_idx = c; + write_byte_idx = 0; + checksum = 0; + + CHECK_PAGE(write_page_idx, true); + + if (page_states[write_page_idx] == PageState::FAIL) { + // Special case for fail + state = State::UNFAIL; + return true; + } + + set_page_state(write_page_idx, PageState::WRITING); + + state = Cfg::DIRECTIONAL ? State::COLLECT : State::SIZE; + + return true; + case State::SIZE: + // Zero means full page size + write_page_size = c; + state = State::COLLECT; + return true; + case State::COLLECT: + pages[write_page_idx][write_byte_idx++] = c; + checksum ^= c; + + // check if still collecting + if (Cfg::PAGE_SIZE == 256) { + // special case for 8-bit, check if rolled back to 0 + if (Cfg::DIRECTIONAL || !write_page_size) { // full 256 bytes + if (write_byte_idx) return true; + } else { + if (write_byte_idx < write_page_size) return true; + } + } else if (Cfg::DIRECTIONAL) { + if (write_byte_idx != Cfg::PAGE_SIZE) return true; + } else { + if (write_byte_idx < write_page_size) return true; + } + + state = State::CHECKSUM; + return true; + case State::CHECKSUM: { + const PageState page_state = (checksum == c) ? PageState::OK : PageState::FAIL; + set_page_state(write_page_idx, page_state); + state = State::MONITOR; + return true; + } + case State::UNFAIL: + if (c == 0) { + set_page_state(write_page_idx, PageState::FREE); + } else { + fatal_error = true; + } + state = State::MONITOR; + return true; + } + } + + template + void SerialPageManager::write_responses() { + if (fatal_error) { + kill(GET_TEXT(MSG_BAD_PAGE)); + return; + } + + // Runs on a set interval also, as responses may get lost. + if (next_response && next_response < millis()) { + page_states_dirty = true; + } + + if (!page_states_dirty) return; + + page_states_dirty = false; + next_response = millis() + Cfg::RESPONSE_INTERVAL_MS; + + SERIAL_ECHO(Cfg::CONTROL_CHAR); + constexpr int state_bits = 2; + constexpr int n_bytes = Cfg::NUM_PAGES >> state_bits; + volatile uint8_t bits_b[n_bytes] = { 0 }; + + for (page_idx_t i = 0 ; i < Cfg::NUM_PAGES ; i++) { + bits_b[i >> state_bits] |= page_states[i] << ((i * state_bits) & 0x7); + } + + uint8_t crc = 0; + for (uint8_t i = 0 ; i < n_bytes ; i++) { + crc ^= bits_b[i]; + SERIAL_ECHO(bits_b[i]); + } + + SERIAL_ECHO(crc); + SERIAL_EOL(); + } + + template + FORCE_INLINE void SerialPageManager::set_page_state(const page_idx_t page_idx, const PageState page_state) { + CHECK_PAGE(page_idx,); + + page_states[page_idx] = page_state; + page_states_dirty = true; + } + + template <> + FORCE_INLINE uint8_t *PageManager::get_page(const page_idx_t page_idx) { + CHECK_PAGE(page_idx, nullptr); + + return pages[page_idx]; + } + + template <> + FORCE_INLINE void PageManager::free_page(const page_idx_t page_idx) { + set_page_state(page_idx, PageState::FREE); + } + +}; + +DirectStepping::PageManager page_manager; + +const uint8_t segment_table[DirectStepping::Config::NUM_SEGMENTS][DirectStepping::Config::SEGMENT_STEPS] PROGMEM = { + + #if STEPPER_PAGE_FORMAT == SP_4x4D_128 + + { 1, 1, 1, 1, 1, 1, 1, 0 }, // 0 = -7 + { 1, 1, 1, 0, 1, 1, 1, 0 }, // 1 = -6 + { 0, 1, 1, 0, 1, 0, 1, 1 }, // 2 = -5 + { 0, 1, 0, 1, 0, 1, 0, 1 }, // 3 = -4 + { 0, 1, 0, 0, 1, 0, 0, 1 }, // 4 = -3 + { 0, 0, 1, 0, 0, 0, 1, 0 }, // 5 = -2 + { 0, 0, 0, 0, 1, 0, 0, 0 }, // 6 = -1 + { 0, 0, 0, 0, 0, 0, 0, 0 }, // 7 = 0 + { 0, 0, 0, 0, 1, 0, 0, 0 }, // 8 = 1 + { 0, 0, 1, 0, 0, 0, 1, 0 }, // 9 = 2 + { 0, 1, 0, 0, 1, 0, 0, 1 }, // 10 = 3 + { 0, 1, 0, 1, 0, 1, 0, 1 }, // 11 = 4 + { 0, 1, 1, 0, 1, 0, 1, 1 }, // 12 = 5 + { 1, 1, 1, 0, 1, 1, 1, 0 }, // 13 = 6 + { 1, 1, 1, 1, 1, 1, 1, 0 }, // 14 = 7 + { 0 } + + #elif STEPPER_PAGE_FORMAT == SP_4x2_256 + + { 0, 0, 0, 0 }, // 0 + { 0, 1, 0, 0 }, // 1 + { 1, 0, 1, 0 }, // 2 + { 1, 1, 1, 0 }, // 3 + + #elif STEPPER_PAGE_FORMAT == SP_4x1_512 + + {0} // Uncompressed format, table not used + + #endif + +}; + +#endif // DIRECT_STEPPING diff --git a/Marlin/src/feature/direct_stepping.h b/Marlin/src/feature/direct_stepping.h new file mode 100644 index 0000000000..4d12f83db7 --- /dev/null +++ b/Marlin/src/feature/direct_stepping.h @@ -0,0 +1,137 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../inc/MarlinConfig.h" + +namespace DirectStepping { + + enum State : char { + MONITOR, NEWLINE, ADDRESS, SIZE, COLLECT, CHECKSUM, UNFAIL + }; + + enum PageState : uint8_t { + FREE, WRITING, OK, FAIL + }; + + // Static state used for stepping through direct stepping pages + struct page_step_state_t { + // Current page + uint8_t *page; + // Current segment + uint16_t segment_idx; + // Current steps within segment + uint8_t segment_steps; + // Segment delta + xyze_uint8_t sd; + // Block delta + xyze_int_t bd; + }; + + template + class SerialPageManager { + public: + + typedef typename Cfg::page_idx_t page_idx_t; + + static bool maybe_store_rxd_char(uint8_t c); + static void write_responses(); + + // common methods for page managers + static void init(); + static uint8_t *get_page(const page_idx_t page_idx); + static void free_page(const page_idx_t page_idx); + + protected: + + typedef typename Cfg::write_byte_idx_t write_byte_idx_t; + + static State state; + static volatile bool fatal_error; + + static volatile PageState page_states[Cfg::NUM_PAGES]; + static volatile bool page_states_dirty; + static millis_t next_response; + + static uint8_t pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE]; + static uint8_t checksum; + static write_byte_idx_t write_byte_idx; + static page_idx_t write_page_idx; + static write_byte_idx_t write_page_size; + + static void set_page_state(const page_idx_t page_idx, const PageState page_state); + }; + + template struct TypeSelector { typedef T type;} ; + template struct TypeSelector { typedef F type; }; + + template + struct config_t { + static constexpr char CONTROL_CHAR = '!'; + + static constexpr int NUM_PAGES = num_pages; + static constexpr int NUM_AXES = num_axes; + static constexpr int BITS_SEGMENT = bits_segment; + static constexpr int DIRECTIONAL = dir ? 1 : 0; + static constexpr int SEGMENTS = segments; + + static constexpr int RAW = (BITS_SEGMENT == 1) ? 1 : 0; + static constexpr int NUM_SEGMENTS = 1 << BITS_SEGMENT; + static constexpr int SEGMENT_STEPS = 1 << (BITS_SEGMENT - DIRECTIONAL - RAW); + static constexpr int TOTAL_STEPS = SEGMENT_STEPS * SEGMENTS; + static constexpr int PAGE_SIZE = (NUM_AXES * BITS_SEGMENT * SEGMENTS) / 8; + + static constexpr millis_t RESPONSE_INTERVAL_MS = 50; + + typedef typename TypeSelector<(PAGE_SIZE>256), uint16_t, uint8_t>::type write_byte_idx_t; + typedef typename TypeSelector<(NUM_PAGES>256), uint16_t, uint8_t>::type page_idx_t; + }; + + template + using SP_4x4D_128 = config_t; + + template + using SP_4x2_256 = config_t; + + template + using SP_4x1_512 = config_t; + + // configured types + typedef STEPPER_PAGE_FORMAT Config; + + template class PAGE_MANAGER; + typedef PAGE_MANAGER PageManager; +}; + +#define SP_4x4D_128 1 +//#define SP_4x4_128 2 +//#define SP_4x2D_256 3 +#define SP_4x2_256 4 +#define SP_4x1_512 5 + +typedef typename DirectStepping::Config::page_idx_t page_idx_t; + +// TODO: use config +typedef DirectStepping::page_step_state_t page_step_state_t; + +extern const uint8_t segment_table[DirectStepping::Config::NUM_SEGMENTS][DirectStepping::Config::SEGMENT_STEPS]; +extern DirectStepping::PageManager page_manager; diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index ac5a60ed93..14f2eea7d9 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -261,6 +261,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 5: G5(); break; // G5: Cubic B_spline #endif + #if ENABLED(DIRECT_STEPPING) + case 6: G6(); break; // G6: Direct Stepper Move + #endif + #if ENABLED(FWRETRACT) case 10: G10(); break; // G10: Retract / Swap Retract case 11: G11(); break; // G11: Recover / Swap Recover diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 92292f609b..573ef0f625 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -402,6 +402,8 @@ private: TERN_(BEZIER_CURVE_SUPPORT, static void G5()); + TERN_(DIRECT_STEPPING, static void G6()); + #if ENABLED(FWRETRACT) static void G10(); static void G11(); diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 91a746dd76..16717de14d 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -99,5 +99,7 @@ void GcodeSuite::G92() { if (sync_XYZ) sync_plan_position(); else if (sync_E) sync_plan_position_e(); - report_current_position(); + #if DISABLED(DIRECT_STEPPING) + report_current_position(); + #endif } diff --git a/Marlin/src/gcode/motion/G6.cpp b/Marlin/src/gcode/motion/G6.cpp new file mode 100644 index 0000000000..4405ff6b9c --- /dev/null +++ b/Marlin/src/gcode/motion/G6.cpp @@ -0,0 +1,61 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../inc/MarlinConfig.h" + +#if ENABLED(DIRECT_STEPPING) + +#include "../../feature/direct_stepping.h" + +#include "../gcode.h" +#include "../../module/planner.h" + +/** + * G6: Direct Stepper Move + */ +void GcodeSuite::G6() { + // TODO: feedrate support? + if (parser.seen('R')) + planner.last_page_step_rate = parser.value_ulong(); + + if (!DirectStepping::Config::DIRECTIONAL) { + if (parser.seen('X')) planner.last_page_dir.x = !!parser.value_byte(); + if (parser.seen('Y')) planner.last_page_dir.y = !!parser.value_byte(); + if (parser.seen('Z')) planner.last_page_dir.z = !!parser.value_byte(); + if (parser.seen('E')) planner.last_page_dir.e = !!parser.value_byte(); + } + + // No index means we just set the state + if (!parser.seen('I')) return; + + // No speed is set, can't schedule the move + if (!planner.last_page_step_rate) return; + + const page_idx_t page_idx = (page_idx_t) parser.value_ulong(); + + uint16_t num_steps = DirectStepping::Config::TOTAL_STEPS; + if (parser.seen('S')) num_steps = parser.value_ushort(); + + planner.buffer_page(page_idx, 0, num_steps); + reset_stepper_timeout(); +} + +#endif // DIRECT_STEPPING diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 2009e7c965..70a1333038 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -323,6 +323,18 @@ #endif #endif +#if ENABLED(DIRECT_STEPPING) + #ifndef STEPPER_PAGES + #define STEPPER_PAGES 16 + #endif + #ifndef STEPPER_PAGE_FORMAT + #define STEPPER_PAGE_FORMAT SP_4x2_256 + #endif + #ifndef PAGE_MANAGER + #define PAGE_MANAGER SerialPageManager + #endif +#endif + // // SD Card connection methods // Defined here so pins and sanity checks can use them diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 11cc7060d4..c8f8907e88 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2923,3 +2923,12 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if SAVED_POSITIONS > 256 #error "SAVED_POSITIONS must be an integer from 0 to 256." #endif + +/** + * Sanity checks for stepper chunk support + */ +#if ENABLED(DIRECT_STEPPING) + #if ENABLED(LIN_ADVANCE) + #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible." + #endif +#endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index df27de57a5..3ee5bea6e4 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -577,6 +577,9 @@ namespace Language_en { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 7d23789df1..dea51ac67f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -151,6 +151,11 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step uint8_t Planner::last_extruder = 0; // Respond to extruder change #endif +#if ENABLED(DIRECT_STEPPING) + uint32_t Planner::last_page_step_rate = 0; + xyze_bool_t Planner::last_page_dir{0}; +#endif + #if EXTRUDERS int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement @@ -235,6 +240,10 @@ void Planner::init() { TERN_(ABL_PLANAR, bed_level_matrix.set_to_identity()); clear_block_buffer(); delay_before_delivering = 0; + #if ENABLED(DIRECT_STEPPING) + last_page_step_rate = 0; + last_page_dir.reset(); + #endif } #if ENABLED(S_CURVE_ACCELERATION) @@ -906,7 +915,7 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e streaming operating conditions. Use for planning optimizations by avoiding recomputing parts of the planner buffer that don't change with the addition of a new block, as describe above. In addition, this block can never be less than block_buffer_tail and will always be pushed forward and maintain - this requirement when encountered by the Planner::discard_current_block() routine during a cycle. + this requirement when encountered by the Planner::release_current_block() routine during a cycle. NOTE: Since the planner only computes on what's in the planner buffer, some motions with lots of short line segments, like G2/3 arcs or complex curves, may seem to move slow. This is because there simply isn't @@ -994,8 +1003,8 @@ void Planner::reverse_pass() { // Perform the reverse pass block_t *current = &block_buffer[block_index]; - // Only consider non sync blocks - if (!TEST(current->flag, BLOCK_BIT_SYNC_POSITION)) { + // Only consider non sync and page blocks + if (!TEST(current->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(current)) { reverse_pass_kernel(current, next); next = current; } @@ -1089,8 +1098,8 @@ void Planner::forward_pass() { // Perform the forward pass block = &block_buffer[block_index]; - // Skip SYNC blocks - if (!TEST(block->flag, BLOCK_BIT_SYNC_POSITION)) { + // Skip SYNC and page blocks + if (!TEST(block->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(block)) { // If there's no previous block or the previous block is not // BUSY (thus, modifiable) run the forward_pass_kernel. Otherwise, // the previous block became BUSY, so assume the current block's @@ -1139,8 +1148,8 @@ void Planner::recalculate_trapezoids() { next = &block_buffer[block_index]; - // Skip sync blocks - if (!TEST(next->flag, BLOCK_BIT_SYNC_POSITION)) { + // Skip sync and page blocks + if (!TEST(next->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(next)) { next_entry_speed = SQRT(next->entry_speed_sqr); if (block) { @@ -2717,6 +2726,69 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #endif } // buffer_line() +#if ENABLED(DIRECT_STEPPING) + + void Planner::buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps) { + if (!last_page_step_rate) { + kill(GET_TEXT(MSG_BAD_PAGE_SPEED)); + return; + } + + uint8_t next_buffer_head; + block_t * const block = get_next_free_block(next_buffer_head); + + block->flag = BLOCK_FLAG_IS_PAGE; + + #if FAN_COUNT > 0 + FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; + #endif + + #if EXTRUDERS > 1 + block->extruder = extruder; + #endif + + block->page_idx = page_idx; + + block->step_event_count = num_steps; + block->initial_rate = + block->final_rate = + block->nominal_rate = last_page_step_rate; // steps/s + + block->accelerate_until = 0; + block->decelerate_after = block->step_event_count; + + // Will be set to last direction later if directional format. + block->direction_bits = 0; + + #define PAGE_UPDATE_DIR(AXIS) \ + if (!last_page_dir[_AXIS(AXIS)]) SBI(block->direction_bits, _AXIS(AXIS)); + + if (!DirectStepping::Config::DIRECTIONAL) { + PAGE_UPDATE_DIR(X); + PAGE_UPDATE_DIR(Y); + PAGE_UPDATE_DIR(Z); + PAGE_UPDATE_DIR(E); + } + + // If this is the first added movement, reload the delay, otherwise, cancel it. + if (block_buffer_head == block_buffer_tail) { + // If it was the first queued block, restart the 1st block delivery delay, to + // give the planner an opportunity to queue more movements and plan them + // As there are no queued movements, the Stepper ISR will not touch this + // variable, so there is no risk setting this here (but it MUST be done + // before the following line!!) + delay_before_delivering = BLOCK_DELAY_FOR_1ST_MOVE; + } + + // Move buffer head + block_buffer_head = next_buffer_head; + + enable_all_steppers(); + stepper.wake_up(); + } + +#endif // DIRECT_STEPPING + /** * Directly set the planner ABC position (and stepper positions) * converting mm (or angles for SCARA) into steps. diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 60dbb612c7..0314758a1d 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -66,6 +66,13 @@ #include "../feature/spindle_laser_types.h" #endif +#if ENABLED(DIRECT_STEPPING) + #include "../feature/direct_stepping.h" + #define IS_PAGE(B) TEST(B->flag, BLOCK_BIT_IS_PAGE) +#else + #define IS_PAGE(B) false +#endif + // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, @@ -90,13 +97,21 @@ enum BlockFlagBit : char { // Sync the stepper counts from the block BLOCK_BIT_SYNC_POSITION + + // Direct stepping page + #if ENABLED(DIRECT_STEPPING) + , BLOCK_BIT_IS_PAGE + #endif }; enum BlockFlag : char { - BLOCK_FLAG_RECALCULATE = _BV(BLOCK_BIT_RECALCULATE), - BLOCK_FLAG_NOMINAL_LENGTH = _BV(BLOCK_BIT_NOMINAL_LENGTH), - BLOCK_FLAG_CONTINUED = _BV(BLOCK_BIT_CONTINUED), - BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) + BLOCK_FLAG_RECALCULATE = _BV(BLOCK_BIT_RECALCULATE) + , BLOCK_FLAG_NOMINAL_LENGTH = _BV(BLOCK_BIT_NOMINAL_LENGTH) + , BLOCK_FLAG_CONTINUED = _BV(BLOCK_BIT_CONTINUED) + , BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) + #if ENABLED(DIRECT_STEPPING) + , BLOCK_FLAG_IS_PAGE = _BV(BLOCK_BIT_IS_PAGE) + #endif }; #if ENABLED(LASER_POWER_INLINE) @@ -180,6 +195,10 @@ typedef struct block_t { final_rate, // The minimal rate at exit acceleration_steps_per_s2; // acceleration steps/sec^2 + #if ENABLED(DIRECT_STEPPING) + page_idx_t page_idx; // Page index used for direct stepping + #endif + #if HAS_CUTTER cutter_power_t cutter_power; // Power level for Spindle, Laser, etc. #endif @@ -296,6 +315,11 @@ class Planner { static uint8_t last_extruder; // Respond to extruder change #endif + #if ENABLED(DIRECT_STEPPING) + static uint32_t last_page_step_rate; // Last page step rate given + static xyze_bool_t last_page_dir; // Last page direction given + #endif + #if EXTRUDERS static int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder static float e_factor[EXTRUDERS]; // The flow percentage and volumetric multiplier combine to scale E movement @@ -726,6 +750,10 @@ class Planner { ); } + #if ENABLED(DIRECT_STEPPING) + static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps); + #endif + /** * Set the planner.position and individual stepper positions. * Used by G92, G28, G29, and other procedures. @@ -811,10 +839,10 @@ class Planner { static block_t* get_current_block(); /** - * "Discard" the block and "release" the memory. + * "Release" the current block so its slot can be reused. * Called when the current block is no longer needed. */ - FORCE_INLINE static void discard_current_block() { + FORCE_INLINE static void release_current_block() { if (has_blocks_queued()) block_buffer_tail = next_block_index(block_buffer_tail); } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 92ee753392..68e75e36e3 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -230,6 +230,10 @@ uint32_t Stepper::advance_divisor = 0, uint32_t Stepper::nextBabystepISR = BABYSTEP_NEVER; #endif +#if ENABLED(DIRECT_STEPPING) + page_step_state_t Stepper::page_step_state; +#endif + int32_t Stepper::ticks_nominal = -1; #if DISABLED(S_CURVE_ACCELERATION) uint32_t Stepper::acc_step_rate; // needed for deceleration start point @@ -1520,11 +1524,7 @@ void Stepper::pulse_phase_isr() { // If we must abort the current block, do so! if (abort_current_block) { abort_current_block = false; - if (current_block) { - axis_did_move = 0; - current_block = nullptr; - planner.discard_current_block(); - } + if (current_block) discard_current_block(); } // If there is no current block, do nothing @@ -1558,46 +1558,160 @@ void Stepper::pulse_phase_isr() { } \ }while(0) - // Start an active pulse, if Bresenham says so, and update position + // Start an active pulse if needed #define PULSE_START(AXIS) do{ \ if (step_needed[_AXIS(AXIS)]) { \ _APPLY_STEP(AXIS, !_INVERT_STEP_PIN(AXIS), 0); \ } \ }while(0) - // Stop an active pulse, if any, and adjust error term + // Stop an active pulse if needed #define PULSE_STOP(AXIS) do { \ if (step_needed[_AXIS(AXIS)]) { \ _APPLY_STEP(AXIS, _INVERT_STEP_PIN(AXIS), 0); \ } \ }while(0) - // Determine if pulses are needed - #if HAS_X_STEP - PULSE_PREP(X); - #endif - #if HAS_Y_STEP - PULSE_PREP(Y); - #endif - #if HAS_Z_STEP - PULSE_PREP(Z); - #endif + // Direct Stepping page? + const bool is_page = IS_PAGE(current_block); + + #if ENABLED(DIRECT_STEPPING) + + if (is_page) { + + #if STEPPER_PAGE_FORMAT == SP_4x4D_128 + + #define PAGE_SEGMENT_UPDATE(AXIS, VALUE, MID) do{ \ + if ((VALUE) == MID) {} \ + else if ((VALUE) < MID) SBI(dm, _AXIS(AXIS)); \ + else CBI(dm, _AXIS(AXIS)); \ + page_step_state.sd[_AXIS(AXIS)] = VALUE; \ + page_step_state.bd[_AXIS(AXIS)] += VALUE; \ + }while(0) + + #define PAGE_PULSE_PREP(AXIS) do{ \ + step_needed[_AXIS(AXIS)] = \ + pgm_read_byte(&segment_table[page_step_state.sd[_AXIS(AXIS)]][page_step_state.segment_steps & 0x7]); \ + }while(0) + + switch (page_step_state.segment_steps) { + case 8: + page_step_state.segment_idx += 2; + page_step_state.segment_steps = 0; + // fallthru + case 0: { + const uint8_t low = page_step_state.page[page_step_state.segment_idx], + high = page_step_state.page[page_step_state.segment_idx + 1]; + uint8_t dm = last_direction_bits; + + PAGE_SEGMENT_UPDATE(X, low >> 4, 7); + PAGE_SEGMENT_UPDATE(Y, low & 0xF, 7); + PAGE_SEGMENT_UPDATE(Z, high >> 4, 7); + PAGE_SEGMENT_UPDATE(E, high & 0xF, 7); + + if (dm != last_direction_bits) { + last_direction_bits = dm; + set_directions(); + } + } break; + + default: break; + } + + PAGE_PULSE_PREP(X), + PAGE_PULSE_PREP(Y), + PAGE_PULSE_PREP(Z), + PAGE_PULSE_PREP(E); + + page_step_state.segment_steps++; + + #elif STEPPER_PAGE_FORMAT == SP_4x2_256 + + #define PAGE_SEGMENT_UPDATE(AXIS, VALUE) \ + page_step_state.sd[_AXIS(AXIS)] = VALUE; \ + page_step_state.bd[_AXIS(AXIS)] += VALUE; + + #define PAGE_PULSE_PREP(AXIS) do{ \ + step_needed[_AXIS(AXIS)] = \ + pgm_read_byte(&segment_table[page_step_state.sd[_AXIS(AXIS)]][page_step_state.segment_steps & 0x3]); \ + }while(0) + + switch (page_step_state.segment_steps) { + case 4: + page_step_state.segment_idx++; + page_step_state.segment_steps = 0; + // fallthru + case 0: { + const uint8_t b = page_step_state.page[page_step_state.segment_idx]; + PAGE_SEGMENT_UPDATE(X, (b >> 6) & 0x3); + PAGE_SEGMENT_UPDATE(Y, (b >> 4) & 0x3); + PAGE_SEGMENT_UPDATE(Z, (b >> 2) & 0x3); + PAGE_SEGMENT_UPDATE(E, (b >> 0) & 0x3); + } break; + default: break; + } + + PAGE_PULSE_PREP(X); + PAGE_PULSE_PREP(Y); + PAGE_PULSE_PREP(Z); + PAGE_PULSE_PREP(E); + + page_step_state.segment_steps++; + + #elif STEPPER_PAGE_FORMAT == SP_4x1_512 + + #define PAGE_PULSE_PREP(AXIS, BITS) do{ \ + step_needed[_AXIS(AXIS)] = (steps >> BITS) & 0x1; \ + if (step_needed[_AXIS(AXIS)]) \ + page_step_state.bd[_AXIS(AXIS)]++; \ + }while(0) + + uint8_t steps = page_step_state.page[page_step_state.segment_idx >> 1]; + + if (page_step_state.segment_idx & 0x1) steps >>= 4; + + PAGE_PULSE_PREP(X, 3); + PAGE_PULSE_PREP(Y, 2); + PAGE_PULSE_PREP(Z, 1); + PAGE_PULSE_PREP(E, 0); + + page_step_state.segment_idx++; - #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) - delta_error.e += advance_dividend.e; - if (delta_error.e >= 0) { - count_position.e += count_direction.e; - #if ENABLED(LIN_ADVANCE) - delta_error.e -= advance_divisor; - // Don't step E here - But remember the number of steps to perform - motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; #else - step_needed.e = true; + #error "Unknown direct stepping page format!" #endif } - #elif HAS_E0_STEP - PULSE_PREP(E); - #endif + + #endif // DIRECT_STEPPING + + if (!is_page) { + // Determine if pulses are needed + #if HAS_X_STEP + PULSE_PREP(X); + #endif + #if HAS_Y_STEP + PULSE_PREP(Y); + #endif + #if HAS_Z_STEP + PULSE_PREP(Z); + #endif + + #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) + delta_error.e += advance_dividend.e; + if (delta_error.e >= 0) { + count_position.e += count_direction.e; + #if ENABLED(LIN_ADVANCE) + delta_error.e -= advance_divisor; + // Don't step E here - But remember the number of steps to perform + motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; + #else + step_needed.e = true; + #endif + } + #elif HAS_E0_STEP + PULSE_PREP(E); + #endif + } #if ISR_MULTI_STEPS if (firstStep) @@ -1676,14 +1790,28 @@ uint32_t Stepper::block_phase_isr() { // If there is a current block if (current_block) { - // If current block is finished, reset pointer + // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { + #if ENABLED(DIRECT_STEPPING) + #if STEPPER_PAGE_FORMAT == SP_4x4D_128 + #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ + count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7; + #elif STEPPER_PAGE_FORMAT == SP_4x1_512 || STEPPER_PAGE_FORMAT == SP_4x2_256 + #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ + count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] * count_direction[_AXIS(AXIS)]; + #endif + + if (IS_PAGE(current_block)) { + PAGE_SEGMENT_UPDATE_POS(X); + PAGE_SEGMENT_UPDATE_POS(Y); + PAGE_SEGMENT_UPDATE_POS(Z); + PAGE_SEGMENT_UPDATE_POS(E); + } + #endif #ifdef FILAMENT_RUNOUT_DISTANCE_MM runout.block_completed(current_block); #endif - axis_did_move = 0; - current_block = nullptr; - planner.discard_current_block(); + discard_current_block(); } else { // Step events not completed yet... @@ -1867,7 +1995,7 @@ uint32_t Stepper::block_phase_isr() { // Sync block? Sync the stepper counts and return while (TEST(current_block->flag, BLOCK_BIT_SYNC_POSITION)) { _set_position(current_block->position); - planner.discard_current_block(); + discard_current_block(); // Try to get a new block if (!(current_block = planner.get_current_block())) @@ -1878,6 +2006,23 @@ uint32_t Stepper::block_phase_isr() { TERN_(POWER_LOSS_RECOVERY, recovery.info.sdpos = current_block->sdpos); + #if ENABLED(DIRECT_STEPPING) + if (IS_PAGE(current_block)) { + page_step_state.segment_steps = 0; + page_step_state.segment_idx = 0; + page_step_state.page = page_manager.get_page(current_block->page_idx); + page_step_state.bd.reset(); + + if (DirectStepping::Config::DIRECTIONAL) + current_block->direction_bits = last_direction_bits; + + if (!page_step_state.page) { + discard_current_block(); + return interval; + } + } + #endif + // Flag all moving axes for proper endstop handling #if IS_CORE diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 793dc8745b..a89d36e98f 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -334,6 +334,10 @@ class Stepper { static uint32_t nextBabystepISR; #endif + #if ENABLED(DIRECT_STEPPING) + static page_step_state_t page_step_state; + #endif + static int32_t ticks_nominal; #if DISABLED(S_CURVE_ACCELERATION) static uint32_t acc_step_rate; // needed for deceleration start point @@ -426,6 +430,17 @@ class Stepper { static void report_a_position(const xyz_long_t &pos); static void report_positions(); + // Discard current block and free any resources + FORCE_INLINE static void discard_current_block() { + #if ENABLED(DIRECT_STEPPING) + if (IS_PAGE(current_block)) + page_manager.free_page(current_block->page_idx); + #endif + current_block = nullptr; + axis_did_move = 0; + planner.release_current_block(); + } + // Quickly stop all steppers FORCE_INLINE static void quick_stop() { abort_current_block = true; } diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index b17d60ba89..ed5713eff8 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -71,8 +71,9 @@ opt_set NUM_SERVOS 1 opt_enable ZONESTAR_LCD Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE BOOT_MARLIN_LOGO_ANIMATED \ AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL \ NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ - PRUSA_MMU2 MMU2_MENUS PRUSA_MMU2_S_MODE FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING -exec_test $1 $2 "RAMPS | ZONESTAR_LCD | MMU2 | Servo Probe | ABL 3-Pt | Debug Leveling | EEPROM | G38 ..." + PRUSA_MMU2 MMU2_MENUS PRUSA_MMU2_S_MODE DIRECT_STEPPING \ + FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING +exec_test $1 $2 "RAMPS | ZONESTAR + Chinese | MMU2 | Servo | 3-Point + Debug | G38 ..." # # Test MINIRAMBO with PWM_MOTOR_CURRENT and many features From aecfc05748d7c82931195831677c7a62bbd9a3ce Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 18:28:27 -0500 Subject: [PATCH 0451/1454] Align slightly in M114 detail --- Marlin/src/gcode/host/M114.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 2e6fff7182..8a31f248bf 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -38,11 +38,12 @@ char str[12]; LOOP_L_N(a, n) { SERIAL_CHAR(' ', axis_codes[a], ':'); + if (pos[a] >= 0) SERIAL_CHAR(' '); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); } SERIAL_EOL(); } - inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, 3); } + inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); } void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { char str[12]; From e6079bd14e3c8b68ff471fbe19cc3ee7a8d2f0d8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 20:16:48 -0500 Subject: [PATCH 0452/1454] Correct endstop noise comment --- Marlin/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 1da43df24c..777f9a534b 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -706,7 +706,7 @@ * Enable if your probe or endstops falsely trigger due to noise. * * - Higher values may affect repeatability or accuracy of some bed probes. - * - To fix noise install a 100nF ceramic capacitor inline with the switch. + * - To fix noise install a 100nF ceramic capacitor in parallel with the switch. * - This feature is not required for common micro-switches mounted on PCBs * based on the Makerbot design, which already have the 100nF capacitor. * From d35dd2a47e78be6a39e99acc1bf5a8e8cbe71ac0 Mon Sep 17 00:00:00 2001 From: Daniel Callander Date: Tue, 12 May 2020 04:01:47 +0100 Subject: [PATCH 0453/1454] Fix babystep / double-click check (#17962) --- Marlin/src/lcd/menu/menu.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index dfd55ae682..9d406c1a37 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -224,7 +224,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co if (on_status_screen()) doubleclick_expire_ms = millis() + DOUBLECLICK_MAX_INTERVAL; } - else if (on_status_screen() && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { + else if (screen == status_screen && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) screen = TERN(BABYSTEP_ZPROBE_OFFSET, lcd_babystep_zoffset, lcd_babystep_z); From df9cad6a53ed16c68b182328b17efb5a4fb8a619 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 20:48:31 -0500 Subject: [PATCH 0454/1454] Correct DEFAULT_MINSEGMENTTIME units --- Marlin/Configuration_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 0acb279fb6..0d36f56caf 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -770,7 +770,7 @@ //#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated // Minimum time that a segment needs to take if the buffer is emptied -#define DEFAULT_MINSEGMENTTIME 20000 // (ms) +#define DEFAULT_MINSEGMENTTIME 20000 // (µs) // Slow down the machine if the look ahead buffer is (by default) half full. // Increase the slowdown divisor for larger buffer sizes. From 0fbedf5b4ccf84344f54429811bf239f75e2f189 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 22:15:19 -0500 Subject: [PATCH 0455/1454] Fix LPC host actions, add tests Fixes #17955 --- Marlin/src/feature/host_actions.h | 3 ++- buildroot/share/tests/LPC1768-tests | 2 ++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 07309274b0..81ef8227ae 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -21,7 +21,8 @@ */ #pragma once -#include "../inc/MarlinConfig.h" +#include "../inc/MarlinConfigPre.h" +#include "../HAL/shared/Marduino.h" void host_action(PGM_P const pstr, const bool eol=true); diff --git a/buildroot/share/tests/LPC1768-tests b/buildroot/share/tests/LPC1768-tests index 9daf919316..332d22396e 100755 --- a/buildroot/share/tests/LPC1768-tests +++ b/buildroot/share/tests/LPC1768-tests @@ -16,6 +16,7 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB opt_enable VIKI2 SDSUPPORT SERIAL_PORT_2 NEOPIXEL_LED + opt_set NEOPIXEL_PIN P1_16 exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" @@ -43,6 +44,7 @@ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT ADAPTIVE_FAN_ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ + HOST_KEEPALIVE_FEATURE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT \ LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER opt_set GRID_MAX_POINTS_X 16 opt_set NOZZLE_TO_PROBE_OFFSET "{ 0, 0, 0 }" From 7664e552f10dae45935d3ba6c23dcf51c2f2f9eb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 23:19:56 -0500 Subject: [PATCH 0456/1454] Finish DOGM progress bar Fixes #17940 --- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 8c67ff10ab..ee0b90bebf 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -597,15 +597,15 @@ void MarlinUI::draw_status_screen() { // Progress bar frame // - if (PAGE_CONTAINS(49, 52)) + if (PAGE_CONTAINS(PROGRESS_BAR_Y, PROGRESS_BAR_Y + 3)) u8g.drawFrame(PROGRESS_BAR_X, PROGRESS_BAR_Y, PROGRESS_BAR_WIDTH, 4); // // Progress bar solid part // - if (PAGE_CONTAINS(50, 51)) // 50-51 (or just 50) - u8g.drawBox(PROGRESS_BAR_X + 1, 50, progress_bar_solid_width, 2); + if (PAGE_CONTAINS(PROGRESS_BAR_Y + 1, PROGRESS_BAR_Y + 2)) + u8g.drawBox(PROGRESS_BAR_X + 1, PROGRESS_BAR_Y + 1, progress_bar_solid_width, 2); if (PAGE_CONTAINS(EXTRAS_BASELINE - INFO_FONT_ASCENT, EXTRAS_BASELINE - 1)) { From c2d66a5df05caf15cd2af16562cec87a16971626 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 23:20:43 -0500 Subject: [PATCH 0457/1454] Tweak JD + Jerk limit --- Marlin/src/module/planner.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index dea51ac67f..3d026c4dae 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2497,9 +2497,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, previous_safe_speed = safe_speed; #if HAS_JUNCTION_DEVIATION - vmax_junction_sqr = _MIN(vmax_junction_sqr, sq(vmax_junction)); + NOMORE(vmax_junction_sqr, sq(vmax_junction)); // Throttle down to max speed #else - vmax_junction_sqr = sq(vmax_junction); + vmax_junction_sqr = sq(vmax_junction); // Go up or down to the new speed #endif #endif // Classic Jerk Limiting From 798dc688473fe1d8c3faaec47b171ff8778d03c7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 23:25:39 -0500 Subject: [PATCH 0458/1454] Combine some conditions --- Marlin/src/inc/Conditionals_LCD.h | 6 +++--- Marlin/src/inc/Conditionals_post.h | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 2ab3f426e2..47a94d0074 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -570,7 +570,7 @@ #if defined(Z_PROBE_SERVO_NR) && Z_PROBE_SERVO_NR >= 0 #define HAS_Z_SERVO_PROBE 1 #endif -#if HAS_Z_SERVO_PROBE || EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) +#if ANY(HAS_Z_SERVO_PROBE, SWITCHING_EXTRUDER, SWITCHING_NOZZLE) #define HAS_SERVO_ANGLES 1 #endif #if !HAS_SERVO_ANGLES @@ -584,7 +584,7 @@ #define HAS_BED_PROBE 1 #endif -#if HAS_BED_PROBE || EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) +#if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING) #define PROBE_SELECTED 1 #endif @@ -682,7 +682,7 @@ #endif // This flag indicates some kind of jerk storage is needed -#if ENABLED(CLASSIC_JERK) || IS_KINEMATIC +#if EITHER(CLASSIC_JERK, IS_KINEMATIC) #define HAS_CLASSIC_JERK 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index fe8778590a..f81577436b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1784,7 +1784,7 @@ #define HAS_AUTO_CHAMBER_FAN 1 #endif -#if HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN +#if ANY(HAS_AUTO_FAN_0, HAS_AUTO_FAN_1, HAS_AUTO_FAN_2, HAS_AUTO_FAN_3, HAS_AUTO_FAN_4, HAS_AUTO_FAN_5, HAS_AUTO_FAN_6, HAS_AUTO_FAN_7, HAS_AUTO_CHAMBER_FAN) #define HAS_AUTO_FAN 1 #endif #define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN) @@ -1892,13 +1892,13 @@ #define HAS_MOTOR_CURRENT_PWM 1 #endif -#if HAS_Z_MS_PINS || HAS_Z2_MS_PINS || HAS_Z3_MS_PINS || HAS_Z4_MS_PINS +#if ANY(HAS_Z_MS_PINS, HAS_Z2_MS_PINS, HAS_Z3_MS_PINS, HAS_Z4_MS_PINS) #define HAS_SOME_Z_MS_PINS 1 #endif -#if HAS_E0_MS_PINS || HAS_E1_MS_PINS || HAS_E2_MS_PINS || HAS_E3_MS_PINS || HAS_E4_MS_PINS || HAS_E5_MS_PINS || HAS_E6_MS_PINS || HAS_E7_MS_PINS +#if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if HAS_X_MS_PINS || HAS_X2_MS_PINS || HAS_Y_MS_PINS || HAS_Y2_MS_PINS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MS_PINS +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MICROSTEPS, HAS_SOME_E_MS_PINS) #define HAS_MICROSTEPS 1 #endif From 98fdc67f1d011dbc31981542a7461ffc60abbc40 Mon Sep 17 00:00:00 2001 From: RudolphRiedel <31180093+RudolphRiedel@users.noreply.github.com> Date: Tue, 12 May 2020 06:51:07 +0200 Subject: [PATCH 0459/1454] Fixes for FYSETC Cheetah (#17935) --- Marlin/Configuration_adv.h | 1 - .../lib/ftdi_eve_touch_ui/pin_mappings.h | 15 --- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 101 ++++++++---------- 3 files changed, 45 insertions(+), 72 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 0d36f56caf..245b2a022f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1381,7 +1381,6 @@ //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping - //#define CHEETAH_TFT_PINMAP // FYSETC Cheetah pin mapping //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, and Stock boards) EXP1 pin mapping //#define GENERIC_EXP2_PINMAP // GENERIC EXP2 pin mapping diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 7476a1108d..236ecf49c6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -163,18 +163,3 @@ #define CLCD_MOD_RESET BTN_EN1 #define CLCD_SPI_CS LCD_PINS_RS #endif - -#ifdef CHEETAH_TFT_PINMAP - #ifndef __MARLIN_FIRMWARE__ - #error "This pin mapping requires Marlin." - #endif - - #define CLCD_MOD_RESET BTN_EN1 - #define CLCD_SPI_CS LCD_PINS_RS - - #if ENABLED(CLCD_USE_SOFT_SPI) - #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE - #define CLCD_SOFT_SPI_MISO LCD_PINS_SCK - #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 - #endif -#endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index a663061f6c..52444008be 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -29,6 +29,7 @@ #define BOARD_INFO_NAME "FYSETC Cheetah" #define BOARD_WEBSITE_URL "fysetc.com" +// https://github.com/FYSETC/Cheetah // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 @@ -103,39 +104,41 @@ // Misc. Functions // #define SDSS PA4 +#define SD_DETECT_PIN PC3 -// -// LCD Pins -// -/** - * _____ - * 5V | 1 2 | GND - * (MOSI) PB15 | 3 4 | PB12 (LCD_EN) - * (SCK) PB13 | 5 6 PC11 (BTN_EN1) - * (LCD_RS) PB14 | 7 8 | PC10 (BTN_EN2) - * (BTN_ENC) PC12 | 9 10| PC9 (BEEPER) - * ----- - * EXP1 - */ +#ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN PB0 +#endif +#ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN PB7 +#endif +#ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN PB6 +#endif -#define EXPA1_03_PIN PB15 -#define EXPA1_04_PIN PB12 -#define EXPA1_05_PIN PB13 -#define EXPA1_06_PIN PC11 -#define EXPA1_07_PIN PB14 -#define EXPA1_08_PIN PC10 -#define EXPA1_09_PIN PC12 -#define EXPA1_10_PIN PC9 +/* +* EXP1 pinout for the LCD according to Fysetcs schematic for the Cheetah board +* _____ +* (Beeper) PC9 | 1 2 | PC12 (BTN_ENC) +* (BTN_EN2) PC11 | 3 4 | PB14 (LCD_RS / MISO) +* (BTN_EN1) PC10 5 6 | PB13 (SCK) +* (LCD_EN) PB12 | 7 8 | PB15 (MOSI) +* GND | 9 10| 5V +* ----- +* EXP1 +* Note: The pin-numbers match the connector correctly and are not in reverse order like on the Ender-3 board. +* Note: Functionally the pins are assigned in the same order as on the Ender-3 board. +* Note: Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. +*/ #if HAS_SPI_LCD - - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN PC9 #if HAS_GRAPHICAL_LCD - #define DOGLCD_A0 EXPA1_07_PIN - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_SCK EXPA1_05_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_A0 PB14 + #define DOGLCD_CS PB12 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 @@ -145,45 +148,31 @@ #endif #endif - #define LCD_PINS_RS EXPA1_04_PIN // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 EXPA1_05_PIN // SCLK - #define LCD_PINS_ENABLE EXPA1_03_PIN // DATA MOSI - - // not connected to a pin - #define SD_DETECT_PIN PC3 - - #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB0 - #endif - #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB7 - #endif - #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB6 - #endif + #define LCD_PINS_RS PB12 // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 PB13 // SCLK + #define LCD_PINS_ENABLE PB15 // DATA MOSI //#define LCD_CONTRAST_INIT 190 #if ENABLED(NEWPANEL) - #define BTN_EN1 EXPA1_06_PIN - #define BTN_EN2 EXPA1_08_PIN - #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 PC10 + #define BTN_EN2 PC11 + #define BTN_ENC PC12 #endif - #endif #if ENABLED(TOUCH_UI_FTDI_EVE) - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN PC9 + #define CLCD_MOD_RESET PC11 + #define CLCD_SPI_CS PB12 - #define BTN_EN1 EXPA1_06_PIN + //#define CLCD_USE_SOFT_SPI // the Cheetah can use hardware-SPI so we do not really need this - #define LCD_PINS_RS EXPA1_04_PIN - - #define CLCD_SPI_BUS 2 - //#define CLCD_USE_SOFT_SPI #if ENABLED(CLCD_USE_SOFT_SPI) - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_SCK EXPA1_07_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define CLCD_SOFT_SPI_MOSI PB15 + #define CLCD_SOFT_SPI_MISO PB14 + #define CLCD_SOFT_SPI_SCLK PB13 + #else + #define CLCD_SPI_BUS 2 #endif #endif From a06a0c5b88edb923db5b45414226ad20fdcfda1d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 11 May 2020 23:56:44 -0500 Subject: [PATCH 0460/1454] Fix SKR/GTR PeripheralPins.c (#17937) * Add a separate GTR board/variant. * Revert SKR Pro MOSI (before 248b7dfa59). --- .../PlatformIO/boards/BigTree_GTR_v1.json | 46 +++ .../variants/BIGTREE_GTR_V1/PeripheralPins.c | 373 ++++++++++++++++++ .../variants/BIGTREE_GTR_V1/PinNamesVar.h | 50 +++ .../variants/BIGTREE_GTR_V1/hal_conf_extra.h | 52 +++ .../variants/BIGTREE_GTR_V1/ldscript.ld | 204 ++++++++++ .../variants/BIGTREE_GTR_V1/variant.cpp | 260 ++++++++++++ .../variants/BIGTREE_GTR_V1/variant.h | 322 +++++++++++++++ .../BIGTREE_SKR_PRO_1v1/PeripheralPins.c | 25 +- platformio.ini | 2 +- 9 files changed, 1320 insertions(+), 14 deletions(-) create mode 100644 buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json create mode 100644 buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h create mode 100644 buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp create mode 100644 buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h diff --git a/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json b/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json new file mode 100644 index 0000000000..669a7520bb --- /dev/null +++ b/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json @@ -0,0 +1,46 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407zgt6", + "variant": "BIGTREE_GTR_V1" + }, + "debug": { + "jlink_device": "STM32F407ZG", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "STM32F407ZG (192k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 196608, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x8008000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "http://www.st.com/en/microcontrollers/stm32f407zg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c new file mode 100644 index 0000000000..4014a519a3 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c @@ -0,0 +1,373 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + * Automatically generated from STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * Note: Commented lines are alternative possibilities which are not used by default. + * If you change them, you should know what you're doing first. + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 + + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 + #endif + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SCL[] = { + {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN0 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BL-TOUCH-SERVO + + // These pins have been defined for something else on the board but they MIGHT be + // used by the user as PWM pins if they aren't used for their primary purpose. + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 I2C connector, SDA pin. Available if I2C isn't used. + // TIM5_CH1 is used by the Servo Library + {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BL-TOUCH port. Available if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + + /** + * Unused by specifications on SKR-Pro. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + #endif + #if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + {PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + #endif + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RTS[] = { + //{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +const PinMap PinMap_UART_CTS[] = { + //{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +#error "CAN bus isn't available on this board. Driver should be disabled." +#endif + +//*** ETHERNET *** +#ifdef HAL_ETH_MODULE_ENABLED +#error "Ethernet port isn't available on this board. Driver should be disabled." +#endif + +//*** No QUADSPI *** + +//*** USB *** +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF used by LCD + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; + +const PinMap PinMap_USB_OTG_HS[] = { /* + #ifdef USE_USB_HS_IN_FS + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + #else + #error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + #endif // USE_USB_HS_IN_FS + */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h new file mode 100644 index 0000000000..b4bb9d45f8 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h @@ -0,0 +1,50 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h new file mode 100644 index 0000000000..e0e8239aac --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h @@ -0,0 +1,52 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) + +#undef HAL_SD_MODULE_ENABLED +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_FLASH_MODULE_ENABLED +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CEC_MODULE_ENABLED +#undef HAL_CRYP_MODULE_ENABLED +#undef HAL_DCMI_MODULE_ENABLED +#undef HAL_DMA2D_MODULE_ENABLED +#undef HAL_ETH_MODULE_ENABLED +#undef HAL_NAND_MODULE_ENABLED +#undef HAL_NOR_MODULE_ENABLED +#undef HAL_PCCARD_MODULE_ENABLED +#undef HAL_SRAM_MODULE_ENABLED +#undef HAL_SDRAM_MODULE_ENABLED +#undef HAL_HASH_MODULE_ENABLED +#undef HAL_EXTI_MODULE_ENABLED +#undef HAL_SMBUS_MODULE_ENABLED +#undef HAL_I2S_MODULE_ENABLED +#undef HAL_IWDG_MODULE_ENABLED +#undef HAL_LTDC_MODULE_ENABLED +#undef HAL_DSI_MODULE_ENABLED +#undef HAL_QSPI_MODULE_ENABLED +#undef HAL_RNG_MODULE_ENABLED +#undef HAL_SAI_MODULE_ENABLED +#undef HAL_IRDA_MODULE_ENABLED +#undef HAL_SMARTCARD_MODULE_ENABLED +#undef HAL_WWDG_MODULE_ENABLED +#undef HAL_HCD_MODULE_ENABLED +#undef HAL_FMPI2C_MODULE_ENABLED +#undef HAL_SPDIFRX_MODULE_ENABLED +#undef HAL_DFSDM_MODULE_ENABLED +#undef HAL_LPTIM_MODULE_ENABLED +#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld new file mode 100644 index 0000000000..0c060d1751 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld @@ -0,0 +1,204 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407ZGTx Device with +** 1024KByte FLASH, 128KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2014 Ac6

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of Ac6 nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200;; /* required amount of heap */ +_Min_Stack_Size = 0x400;; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x8008000, LENGTH = 1024K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text ALIGN(4): + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata ALIGN(4): + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp new file mode 100644 index 0000000000..1486b21830 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp @@ -0,0 +1,260 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + */ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +// This array allows to wrap Arduino pin number(Dx or x) +// to STM32 PinName (PX_n) +const PinName digitalPin[] = { +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + PC_13, //D0 + PC_14, //D1 - OSC32_IN + PC_15, //D2 - OSC32_OUT + PH_0, //D3 - OSC_IN + PH_1, //D4 - OSC_OUT + PB_2, //D5 - BOOT1 + PB_10, //D6 - 1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + PB_11, //D7 - 1:I2C2_SDA / USART3_RX / TIM2_CH4 + PB_12, //D8 - 1:SPI2_NSS / OTG_HS_ID + PB_13, //D9 - 1:SPI2_SCK 2:OTG_HS_VBUS + PB_14, //D10 - 1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + PB_15, //D11 - SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + PC_6, //D12 - 1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + PC_7, //D13 - 1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + PC_8, //D14 - 1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + PC_9, //D15 - 1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + PA_8, //D16 - 1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + PA_9, //D17 - 1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + PA_10, //D18 - 1:USART1_RX / TIM1_CH3 / OTG_FS_ID + PA_11, //D19 - 1:TIM1_CH4 / OTG_FS_DM + PA_12, //D20 - 1:OTG_FS_DP + PA_13, //D21 - 0:JTMS-SWDIO + PA_14, //D22 - 0:JTCK-SWCLK + PA_15, //D23 - 0:JTDI 1:SPI3_NSS / SPI1_NSS + PC_10, //D24 - 1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + PC_11, //D25 - 1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + PC_12, //D26 - 1:UART5_TX / SPI3_MOSI / SDIO_CK + PD_2, //D27 - 1:UART5_RX / SDIO_CMD + PB_3, //D28 - 0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + PB_4, //D29 - 0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + PB_5, //D30 - 1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + PB_6, //D31 - 1:I2C1_SCL / TIM4_CH1 / USART1_TX + PB_7, //D32 - 1:I2C1_SDA / TIM4_CH2 / USART1_RX + PB_8, //D33 - 1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + PB_9, //D34 - 1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + PA_0, //D35/A0 - 1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + PA_1, //D36/A1 - 1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + PA_2, //D37/A2 - 1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + PA_3, //D38/A3 - 1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + PA_4, //D39/A4 - NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + PA_5, //D40/A5 - NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + PA_6, //D41/A6 - 1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + PA_7, //D42/A7 - 1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + PB_0, //D43/A8 - 1:TIM3_CH3 2:ADC12_IN8 + PB_1, //D44/A9 - 1:TIM3_CH4 2:ADC12_IN9 + PC_0, //D45/A10 - 1: 2:ADC123_IN10 + PC_1, //D46/A11 - 1: 2:ADC123_IN11 + PC_2, //D47/A12 - 1:SPI2_MISO 2:ADC123_IN12 + PC_3, //D48/A13 - 1:SPI2_MOSI 2:ADC123_IN13 + PC_4, //D49/A14 - 1: 2:ADC12_IN14 + PC_5, //D50/A15 - 1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + PF_3, //D51/A16 - 1:FSMC_A3 2:ADC3_IN9 + PF_4, //D52/A17 - 1:FSMC_A4 2:ADC3_IN14 + PF_5, //D53/A18 - 1:FSMC_A5 2:ADC3_IN15 + PF_6, //D54/A19 - 1:TIM10_CH1 2:ADC3_IN4 + PF_7, //D55/A20 - 1:TIM11_CH1 2:ADC3_IN5 + PF_8, //D56/A21 - 1:TIM13_CH1 2:ADC3_IN6 + PF_9, //D57/A22 - 1;TIM14_CH1 2:ADC3_IN7 + PF_10, //D58/A23 - 2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + PE_2, //D59 - 1:FSMC_A23 + PE_3, //D60 - 1:FSMC_A19 + PE_4, //D61 - 1:FSMC_A20 + PE_5, //D62 - 1:FSMC_A21 + PE_6, //D63 - 1:FSMC_A22 + PE_7, //D64 - 1:FSMC_D4 + PE_8, //D65 - 1:FSMC_D5 + PE_9, //D66 - 1:FSMC_D6 / TIM1_CH1 + PE_10, //D67 - 1:FSMC_D7 + PE_11, //D68 - 1:FSMC_D8 / TIM1_CH2 + PE_12, //D69 - 1:FSMC_D9 + PE_13, //D70 - 1:FSMC_D10 / TIM1_CH3 + PE_14, //D71 - 1:FSMC_D11 / TIM1_CH4 + PE_15, //D72 - 1:FSMC_D12 + PD_8, //D73 - 1:FSMC_D13 / USART3_TX + PD_9, //D74 - 1:FSMC_D14 / USART3_RX + PD_10, //D75 - 1:FSMC_D15 + PD_11, //D76 - 1:FSMC_A16 + PD_12, //D77 - 1:FSMC_A17 / TIM4_CH1 + PD_13, //D78 - 1:FSMC_A18 / TIM4_CH2 + PD_14, //D79 - 1:FSMC_D0 / TIM4_CH3 + PD_15, //D80 - 1:FSMC_D1 / TIM4_CH4 + PD_0, //D81 - 1:FSMC_D2 + PD_1, //D82 - 1:FSMC_D3 + PD_3, //D83 - 1:FSMC_CLK + PD_4, //D84 - 1:FSMC_NOE + PD_5, //D85 - 1:USART2_TX + PD_6, //D86 - 1:USART2_RX + PD_7, //D87 + PE_0, //D88 + PE_1, //D89 +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + PF_0, //D90 - 1:FSMC_A0 / I2C2_SDA + PF_1, //D91 - 1:FSMC_A1 / I2C2_SCL + PF_2, //D92 - 1:FSMC_A2 + PF_11, //D93 + PF_12, //D94 - 1:FSMC_A6 + PF_13, //D95 - 1:FSMC_A7 + PF_14, //D96 - 1:FSMC_A8 + PF_15, //D97 - 1:FSMC_A9 + PG_0, //D98 - 1:FSMC_A10 + PG_1, //D99 - 1:FSMC_A11 + PG_2, //D100 - 1:FSMC_A12 + PG_3, //D101 - 1:FSMC_A13 + PG_4, //D102 - 1:FSMC_A14 + PG_5, //D103 - 1:FSMC_A15 + PG_6, //D104 + PG_7, //D105 + PG_8, //D106 + PG_9, //D107 - 1:USART6_RX + PG_10, //D108 - 1:FSMC_NE3 + PG_11, //D109 + PG_12, //D110 - 1:FSMC_NE4 + PG_13, //D111 - 1:FSMC_A24 + PG_14, //D112 - 1:FSMC_A25 / USART6_TX + PG_15, //D113 +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + PI_8, //D114 + PI_9, //D115 + PI_10, //D116 + PI_11, //D117 + PH_2, //D118 + PH_3, //D119 + PH_4, //D120 - 1:I2C2_SCL + PH_5, //D121 - 1:I2C2_SDA + PH_6, //D122 - 1:TIM12_CH1 + PH_7, //D123 - 1:I2C3_SCL + PH_8, //D124 - 1:I2C3_SDA + PH_9, //D125 - 1:TIM12_CH2 + PH_10, //D126 - 1:TIM5_CH1 + PH_11, //D127 - 1:TIM5_CH2 + PH_12, //D128 - 1:TIM5_CH3 + PH_13, //D129 + PH_14, //D130 + PH_15, //D131 + PI_0, //D132 - 1:TIM5_CH4 / SPI2_NSS + PI_1, //D133 - 1:SPI2_SCK + PI_2, //D134 - 1:TIM8_CH4 /SPI2_MISO + PI_3, //D135 - 1:SPI2_MOS + PI_4, //D136 + PI_5, //D137 - 1:TIM8_CH1 + PI_6, //D138 - 1:TIM8_CH2 + PI_7, //D139 - 1:TIM8_CH3 +#endif +}; + +#ifdef __cplusplus +} +#endif + +// ------------------------ + +#ifdef __cplusplus +extern "C" { +#endif + + /** + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config() { + + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + + /**Configure the main internal regulator output voltage + */ + __HAL_RCC_PWR_CLK_ENABLE(); + + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 8; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + _Error_Handler(__FILE__, __LINE__); + } + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) { + _Error_Handler(__FILE__, __LINE__); + } + + /**Configure the Systick interrupt time + */ + HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000); + + /**Configure the Systick + */ + HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); + + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h new file mode 100644 index 0000000000..1ba0a18d6a --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h @@ -0,0 +1,322 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#ifdef STM32F405RX + #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio + #define STM32F4X_GPIO_NUM 51 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5VX) + #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio + #define STM32F4X_GPIO_NUM 82 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5ZX) + #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio + #define STM32F4X_GPIO_NUM 114 + #define STM32F4X_ADC_NUM 24 +#elif defined(STM32F407IX) + #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio + #define STM32F4X_GPIO_NUM 140 + #define STM32F4X_ADC_NUM 24 +#else + #error "no match MCU defined" +#endif + +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + #define PC13 0 + #define PC14 1 //OSC32_IN + #define PC15 2 //OSC32_OUT + #define PH0 3 //OSC_IN + #define PH1 4 //OSC_OUT + #define PB2 5 //BOOT1 + #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 + #define PB12 8 //1:SPI2_NSS / OTG_HS_ID + #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS + #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID + #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM + #define PA12 20 //1:OTG_FS_DP + #define PA13 21 //0:JTMS-SWDIO + #define PA14 22 //0:JTCK-SWCLK + #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS + #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK + #define PD2 27 //1:UART5_RX / SDIO_CMD + #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX + #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX + #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 + #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 + #define PC0 45 //1: 2:ADC123_IN10 + #define PC1 46 //1: 2:ADC123_IN11 + #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 + #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 + #define PC4 49 //1: 2:ADC12_IN14 + #define PC5 50 //1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 + #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 + #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 + #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 + #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 + #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 + #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 + #define PF10 58 //2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 + #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 + #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 + #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 + #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 + #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 + #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 + #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 + #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 + #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 + #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 + #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 + #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 + #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 + #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX + #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX + #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 + #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 + #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 + #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 + #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 + #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 + #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 + #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 + #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK + #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE + #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX + #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX + #define PD7 (63+STM32F4X_ADC_NUM) + #define PE0 (64+STM32F4X_ADC_NUM) + #define PE1 (65+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA + #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL + #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 + #define PF11 (69+STM32F4X_ADC_NUM) + #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 + #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 + #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 + #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 + #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 + #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 + #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 + #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 + #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 + #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 + #define PG6 (80+STM32F4X_ADC_NUM) + #define PG7 (81+STM32F4X_ADC_NUM) + #define PG8 (82+STM32F4X_ADC_NUM) + #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX + #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 + #define PG11 (85+STM32F4X_ADC_NUM) + #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 + #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 + #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX + #define PG15 (89+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + #define PI8 (90+STM32F4X_ADC_NUM) + #define PI9 (91+STM32F4X_ADC_NUM) + #define PI10 (92+STM32F4X_ADC_NUM) + #define PI11 (93+STM32F4X_ADC_NUM) + #define PH2 (94+STM32F4X_ADC_NUM) + #define PH3 (95+STM32F4X_ADC_NUM) + #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL + #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA + #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 + #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL + #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA + #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 + #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 + #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 + #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 + #define PH13 (105+STM32F4X_ADC_NUM) + #define PH14 (106+STM32F4X_ADC_NUM) + #define PH15 (107+STM32F4X_ADC_NUM) + #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS + #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK + #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO + #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS + #define PI4 (112+STM32F4X_ADC_NUM) + #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 + #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 + #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 +#endif + + +// This must be a literal +#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) +// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) +#define NUM_ANALOG_FIRST 35 + +// Below ADC, DAC and PWM definitions already done in the core +// Could be redefined here if needed +// ADC resolution is 12bits +//#define ADC_RESOLUTION 12 +//#define DACC_RESOLUTION 12 + +// PWM resolution +/* + * BEWARE: + * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) + * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) + */ +//#define PWM_FREQUENCY 20000 +//The bottom values are the default and don't need to be redefined +//#define PWM_RESOLUTION 8 +//#define PWM_MAX_DUTY_CYCLE 255 + +// On-board LED pin number +#define LED_BUILTIN PA7 +#define LED_GREEN LED_BUILTIN + +// Below SPI and I2C definitions already done in the core +// Could be redefined here if differs from the default one +// SPI Definitions +#define PIN_SPI_MOSI PB15 +#define PIN_SPI_MISO PB14 +#define PIN_SPI_SCK PB13 +#define PIN_SPI_SS PB12 + +// I2C Definitions +#if STM32F4X_PIN_NUM >= 176 + #define PIN_WIRE_SDA PH5 + #define PIN_WIRE_SCL PH4 +#else + #define PIN_WIRE_SDA PB7 + #define PIN_WIRE_SCL PB6 +#endif + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM2 +#define TIMER_SERVO TIM5 // Only 1 Servo PIN on SKR-PRO, so use the same timer as defined in PeripheralPins +#define TIMER_SERIAL TIM7 + +// UART Definitions +//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below +#define ENABLE_HWSERIAL3 +#define ENABLE_HWSERIAL6 + +// Define here Serial instance number to map on Serial generic name (if not already used by SerialUSB) +#define SERIAL_UART_INSTANCE 1 //1 for Serial = Serial1 (USART1) + +// DEBUG_UART could be redefined to print on another instance than 'Serial' +//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 +// DEBUG_UART baudrate, default: 9600 if not defined +//#define DEBUG_UART_BAUDRATE x +// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART +//#define DEBUG_PINNAME_TX PX_n // PinName used for TX + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number +// Used when user instanciate a hardware Serial using its peripheral name. +// Example: HardwareSerial mySerial(USART3); +// will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 +#define PIN_SERIAL3_RX PD9 +#define PIN_SERIAL3_TX PD8 +#define PIN_SERIAL6_RX PC7 +#define PIN_SERIAL6_TX PC6 +//#define PIN_SERIALLP1_RX x // For LPUART1 RX +//#define PIN_SERIALLP1_TX x // For LPUART1 TX + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus +// These serial port names are intended to allow libraries and architecture-neutral +// sketches to automatically default to the correct port name for a particular type +// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, +// the first hardware serial port whose RX/TX pins are not dedicated to another use. +// +// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor +// +// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial +// +// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library +// +// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. +// +// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX +// pins are NOT connected to anything by default. +#define SERIAL_PORT_MONITOR Serial +#define SERIAL_PORT_HARDWARE Serial1 +#define SERIAL_PORT_HARDWARE_OPEN Serial3 +#define SERIAL_PORT_HARDWARE_OPEN1 Serial6 +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c index a28e712e0d..6dc8b05158 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c @@ -94,7 +94,7 @@ const PinMap PinMap_I2C_SDA[] = { #if STM32F4X_PIN_NUM >= 176 {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else + #else {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, #endif #endif @@ -113,7 +113,7 @@ const PinMap PinMap_I2C_SCL[] = { //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else + #else {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, #endif #endif @@ -152,8 +152,8 @@ const PinMap PinMap_PWM[] = { */ //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" - {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 @@ -186,7 +186,7 @@ const PinMap PinMap_PWM[] = { //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N @@ -199,15 +199,15 @@ const PinMap PinMap_PWM[] = { //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 @@ -295,8 +295,7 @@ const PinMap PinMap_UART_CTS[] = { #ifdef HAL_SPI_MODULE_ENABLED const PinMap PinMap_SPI_MOSI[] = { - //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {NC, NP, 0} diff --git a/platformio.ini b/platformio.ini index 81855b3030..413b5201da 100644 --- a/platformio.ini +++ b/platformio.ini @@ -777,7 +777,7 @@ debug_init_break = [env:BIGTREE_GTR_V1_0] platform = ststm32@>=5.7.0 platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} -board = BigTree_SKR_Pro +board = BigTree_GTR_v1 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407IG\" From 181739d0d1a54ab01c4f97678f04ae43ebb1facd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 00:09:18 -0500 Subject: [PATCH 0461/1454] Move inline laser state to fix EEPROM error --- Marlin/src/feature/spindle_laser.h | 10 +++++----- Marlin/src/module/planner.cpp | 8 ++++++-- Marlin/src/module/planner.h | 9 +++++---- Marlin/src/module/stepper.cpp | 4 ++-- 4 files changed, 18 insertions(+), 13 deletions(-) diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 0c2e569aa6..2e86395098 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -137,7 +137,7 @@ public: #if ENABLED(LASER_POWER_INLINE) // Force disengage planner power control - static inline void inline_disable() { planner.settings.laser.status = 0; planner.settings.laser.power = 0; isOn = false;} + static inline void inline_disable() { planner.laser.status = 0; planner.laser.power = 0; isOn = false;} // Inline modes of all other functions; all enable planner inline power control static inline void inline_enabled(const bool enable) { enable ? inline_power(SPEED_POWER_STARTUP) : inline_ocr_power(0); } @@ -146,8 +146,8 @@ public: #if ENABLED(SPINDLE_LASER_PWM) inline_ocr_power(translate_power(pwr)); #else - planner.settings.laser.status = enabled(pwr) ? 0x03 : 0x01; - planner.settings.laser.power = pwr; + planner.laser.status = enabled(pwr) ? 0x03 : 0x01; + planner.laser.power = pwr; #endif } @@ -155,8 +155,8 @@ public: #if ENABLED(SPINDLE_LASER_PWM) static inline void inline_ocr_power(const uint8_t pwr) { - planner.settings.laser.status = pwr ? 0x03 : 0x01; - planner.settings.laser.power = pwr; + planner.laser.status = pwr ? 0x03 : 0x01; + planner.laser.power = pwr; } #endif #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 3d026c4dae..6058486510 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -128,6 +128,10 @@ uint8_t Planner::delay_before_delivering; // This counter delays delivery planner_settings_t Planner::settings; // Initialized by settings.load() +#if ENABLED(LASER_POWER_INLINE) + laser_state_t Planner::laser; // Current state for blocks +#endif + uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step @@ -1799,8 +1803,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Update block laser power #if ENABLED(LASER_POWER_INLINE) - block->laser.status = settings.laser.status; - block->laser.power = settings.laser.power; + block->laser.status = laser.status; + block->laser.power = laser.power; #endif // Number of steps for each axis diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 0314758a1d..6c5218cd6f 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -248,7 +248,7 @@ typedef struct block_t { * as it avoids floating points during move loop */ uint8_t power; - } settings_laser_t; + } laser_state_t; #endif typedef struct { @@ -261,9 +261,6 @@ typedef struct { travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate - #if ENABLED(LASER_POWER_INLINE) - settings_laser_t laser; - #endif } planner_settings_t; #if DISABLED(SKEW_CORRECTION) @@ -334,6 +331,10 @@ class Planner { static planner_settings_t settings; + #if ENABLED(LASER_POWER_INLINE) + static laser_state_t laser; + #endif + static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 static float steps_to_mm[XYZE_N]; // Millimeters per step diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 68e75e36e3..4a40e3f22d 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2239,11 +2239,11 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(LASER_POWER_INLINE_CONTINUOUS) else { // No new block found; so apply inline laser parameters // This should mean ending file with 'M5 I' will stop the laser; thus the inline flag isn't needed - const uint8_t stat = planner.settings.laser.status; + const uint8_t stat = planner.laser.status; if (TEST(stat, 0)) { // Planner controls the laser #if ENABLED(SPINDLE_LASER_PWM) if (TEST(stat, 1)) // Laser is on - cutter.set_ocr_power(planner.settings.laser.power); + cutter.set_ocr_power(planner.laser.power); else cutter.set_power(0); #else From ab19a27f6334a12519b5f66af167aa4518cea4f0 Mon Sep 17 00:00:00 2001 From: espr14 <46957311+espr14@users.noreply.github.com> Date: Tue, 12 May 2020 08:01:16 +0200 Subject: [PATCH 0462/1454] Prevent some macro pitfalls (#17956) Co-authored-by: espr14 --- Marlin/src/core/macros.h | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index edab6ae5bc..edf041f70a 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -102,7 +102,7 @@ #define SBI32(n,b) (n |= _BV32(b)) #define CBI32(n,b) (n &= ~_BV32(b)) -#define cu(x) ((x)*(x)*(x)) +#define cu(x) ({__typeof__(x) _x = (x); (_x)*(_x)*(_x);}) #define RADIANS(d) ((d)*float(M_PI)/180.0f) #define DEGREES(r) ((r)*180.0f/float(M_PI)) #define HYPOT2(x,y) (sq(x)+sq(y)) @@ -110,7 +110,7 @@ #define CIRCLE_AREA(R) (float(M_PI) * sq(float(R))) #define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R)) -#define SIGN(a) ((a>0)-(a<0)) +#define SIGN(a) ({__typeof__(a) _a = (a); (_a>0)-(_a<0);}) #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1))) // Macros to constrain values @@ -130,8 +130,6 @@ #else - // Using GCC extensions, but Travis GCC version does not like it and gives - // "error: statement-expressions are not allowed outside functions nor in template-argument lists" #define NOLESS(v, n) \ do{ \ __typeof__(n) _n = (n); \ @@ -269,7 +267,7 @@ #define NEAR(x,y) NEAR_ZERO((x)-(y)) #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0 : (1 / float(x))) -#define FIXFLOAT(f) (f + (f < 0 ? -0.00005f : 0.00005f)) +#define FIXFLOAT(f) ({__typeof__(f) _f = (f); _f + (_f < 0 ? -0.00005f : 0.00005f);}) // // Maths macros that can be overridden by HAL From d4aa1977443d51c483f22a177dfd65bd241a2b29 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 01:41:10 -0500 Subject: [PATCH 0463/1454] Add MAP macro --- Marlin/src/core/macros.h | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index edf041f70a..ebcb9ebcfb 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -480,3 +480,14 @@ #define RREPEAT(N,OP) RREPEAT_S(0,N,OP) #define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V)) #define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V) + +// See https://github.com/swansontec/map-macro +#define MAP_OUT +#define MAP_END(...) +#define MAP_GET_END() 0, MAP_END +#define MAP_NEXT0(test, next, ...) next MAP_OUT +#define MAP_NEXT1(test, next) MAP_NEXT0 (test, next, 0) +#define MAP_NEXT(test, next) MAP_NEXT1 (MAP_GET_END test, next) +#define MAP0(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP1) (f, peek, __VA_ARGS__) +#define MAP1(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP0) (f, peek, __VA_ARGS__) +#define MAP(f, ...) EVAL512 (MAP1 (f, __VA_ARGS__, (), 0)) From d853a70556f89c76dbf02b3723d71d9b56c2c4cf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 01:45:28 -0500 Subject: [PATCH 0464/1454] Remove strcpy compile warning --- Marlin/src/gcode/queue.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 4d7d107ebd..4b974113fb 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -216,13 +216,12 @@ bool GCodeQueue::process_injected_command() { gcode.process_parsed_command(); } - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wrestrict" - // Copy the next command into place - strcpy(injected_commands, &injected_commands[i + (c != '\0')]); - - #pragma GCC diagnostic pop + for ( + uint8_t d = 0, s = i + !!c; // dst, src + (injected_commands[d] = injected_commands[s]); // copy, exit if 0 + d++, s++ // next dst, src + ); return true; } From 73e0937f499e10db35e8735749a1549128a8832d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 01:59:39 -0500 Subject: [PATCH 0465/1454] Fix HAS_MICROSTEPS if only Z --- Marlin/src/inc/Conditionals_post.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index f81577436b..7d5cb060b9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1898,7 +1898,7 @@ #if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MICROSTEPS, HAS_SOME_E_MS_PINS) +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS) #define HAS_MICROSTEPS 1 #endif From ac6a58010daae38b7fb9d96a704597cb727ca2cb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 02:02:25 -0500 Subject: [PATCH 0466/1454] Reorder RAMBo tests --- buildroot/share/tests/rambo-tests | 54 +++++++++++++++---------------- 1 file changed, 27 insertions(+), 27 deletions(-) diff --git a/buildroot/share/tests/rambo-tests b/buildroot/share/tests/rambo-tests index 7fab4fc6ca..fbe27a2658 100644 --- a/buildroot/share/tests/rambo-tests +++ b/buildroot/share/tests/rambo-tests @@ -6,33 +6,6 @@ # exit on first failure set -e -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_EINSY_RAMBO -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2130 -opt_set Z_DRIVER_TYPE TMC2130 -opt_set E0_DRIVER_TYPE TMC2130 -exec_test $1 $2 "Default Configuration" - -# -# Full size Rambo Dual Endstop CNC -# -restore_configs -opt_set MOTHERBOARD BOARD_RAMBO -opt_set EXTRUDERS 0 -opt_set TEMP_SENSOR_0 999 -opt_set DUMMY_THERMISTOR_999_VALUE 170 -opt_set DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' -opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ - S_CURVE_ACCELERATION X_DUAL_STEPPER_DRIVERS X_DUAL_ENDSTOPS Y_DUAL_STEPPER_DRIVERS Y_DUAL_ENDSTOPS \ - ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES -opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS -exec_test $1 $2 "Rambo CNC Configuration" - # # Lots of options - Formerly the first Mega2560 test # @@ -68,5 +41,32 @@ opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL exec_test $1 $2 "RAMBO | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear | Advanced Pause | PLR | LEDs ..." +# +# Full size Rambo Dual Endstop CNC +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO +opt_set EXTRUDERS 0 +opt_set TEMP_SENSOR_0 999 +opt_set DUMMY_THERMISTOR_999_VALUE 170 +opt_set DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' +opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ + S_CURVE_ACCELERATION X_DUAL_STEPPER_DRIVERS X_DUAL_ENDSTOPS Y_DUAL_STEPPER_DRIVERS Y_DUAL_ENDSTOPS \ + ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES +opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS +exec_test $1 $2 "Rambo CNC Configuration" + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_EINSY_RAMBO +opt_set X_DRIVER_TYPE TMC2130 +opt_set Y_DRIVER_TYPE TMC2130 +opt_set Z_DRIVER_TYPE TMC2130 +opt_set E0_DRIVER_TYPE TMC2130 +exec_test $1 $2 "Einsy RAMBo with TMC2130" + # clean up restore_configs From 219812e3bbd1dd90cff54faf64b822dc2b05bdd6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 02:11:16 -0500 Subject: [PATCH 0467/1454] Squish microstep_readings --- Marlin/src/module/stepper.cpp | 115 ++++++++++++++-------------------- 1 file changed, 48 insertions(+), 67 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 4a40e3f22d..63fee87d00 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -3420,95 +3420,76 @@ void Stepper::report_positions() { } void Stepper::microstep_readings() { - SERIAL_ECHOLNPGM("MS1|MS2|MS3 Pins"); + #define PIN_CHAR(P) SERIAL_CHAR('0' + READ(P##_PIN)) + #define MS_LINE(A) do{ SERIAL_ECHOPGM(" " STRINGIFY(A) ":"); PIN_CHAR(A##_MS1); PIN_CHAR(A##_MS2); }while(0) + SERIAL_ECHOPGM("MS1|2|3 Pins"); #if HAS_X_MS_PINS - SERIAL_ECHOPGM("X: "); - SERIAL_CHAR('0' + READ(X_MS1_PIN), '0' + READ(X_MS2_PIN) - #if PIN_EXISTS(X_MS3) - , '0' + READ(X_MS3_PIN) - #endif - ); + MS_LINE(X); + #if PIN_EXISTS(X_MS3) + PIN_CHAR(X_MS3); + #endif #endif #if HAS_Y_MS_PINS - SERIAL_ECHOPGM("Y: "); - SERIAL_CHAR('0' + READ(Y_MS1_PIN), '0' + READ(Y_MS2_PIN) - #if PIN_EXISTS(Y_MS3) - , '0' + READ(Y_MS3_PIN) - #endif - ); + MS_LINE(Y); + #if PIN_EXISTS(Y_MS3) + PIN_CHAR(Y_MS3); + #endif #endif #if HAS_Z_MS_PINS - SERIAL_ECHOPGM("Z: "); - SERIAL_CHAR('0' + READ(Z_MS1_PIN), '0' + READ(Z_MS2_PIN) - #if PIN_EXISTS(Z_MS3) - , '0' + READ(Z_MS3_PIN) - #endif - ); + MS_LINE(Z); + #if PIN_EXISTS(Z_MS3) + PIN_CHAR(Z_MS3); + #endif #endif #if HAS_E0_MS_PINS - SERIAL_ECHOPGM("E0: "); - SERIAL_CHAR('0' + READ(E0_MS1_PIN), '0' + READ(E0_MS2_PIN) - #if PIN_EXISTS(E0_MS3) - , '0' + READ(E0_MS3_PIN) - #endif - ); + MS_LINE(E0); + #if PIN_EXISTS(E0_MS3) + PIN_CHAR(E0_MS3); + #endif #endif #if HAS_E1_MS_PINS - SERIAL_ECHOPGM("E1: "); - SERIAL_CHAR('0' + READ(E1_MS1_PIN), '0' + READ(E1_MS2_PIN) - #if PIN_EXISTS(E1_MS3) - , '0' + READ(E1_MS3_PIN) - #endif - ); + MS_LINE(E1); + #if PIN_EXISTS(E1_MS3) + PIN_CHAR(E1_MS3); + #endif #endif #if HAS_E2_MS_PINS - SERIAL_ECHOPGM("E2: "); - SERIAL_CHAR('0' + READ(E2_MS1_PIN), '0' + READ(E2_MS2_PIN) - #if PIN_EXISTS(E2_MS3) - , '0' + READ(E2_MS3_PIN) - #endif - ); + MS_LINE(E2); + #if PIN_EXISTS(E2_MS3) + PIN_CHAR(E2_MS3); + #endif #endif #if HAS_E3_MS_PINS - SERIAL_ECHOPGM("E3: "); - SERIAL_CHAR('0' + READ(E3_MS1_PIN), '0' + READ(E3_MS2_PIN) - #if PIN_EXISTS(E3_MS3) - , '0' + READ(E3_MS3_PIN) - #endif - ); + MS_LINE(E3); + #if PIN_EXISTS(E3_MS3) + PIN_CHAR(E3_MS3); + #endif #endif #if HAS_E4_MS_PINS - SERIAL_ECHOPGM("E4: "); - SERIAL_CHAR('0' + READ(E4_MS1_PIN), '0' + READ(E4_MS2_PIN) - #if PIN_EXISTS(E4_MS3) - , '0' + READ(E4_MS3_PIN) - #endif - ); + MS_LINE(E4); + #if PIN_EXISTS(E4_MS3) + PIN_CHAR(E4_MS3); + #endif #endif #if HAS_E5_MS_PINS - SERIAL_ECHOPGM("E5: "); - SERIAL_CHAR('0' + READ(E5_MS1_PIN), '0' + READ(E5_MS2_PIN) - #if PIN_EXISTS(E5_MS3) - , '0' + READ(E5_MS3_PIN) - #endif - ); + MS_LINE(E5); + #if PIN_EXISTS(E5_MS3) + PIN_CHAR(E5_MS3); + #endif #endif #if HAS_E6_MS_PINS - SERIAL_ECHOPGM("E6: "); - SERIAL_CHAR('0' + READ(E6_MS1_PIN), '0' + READ(E6_MS2_PIN) - #if PIN_EXISTS(E6_MS3) - , '0' + READ(E6_MS3_PIN) - #endif - ); + MS_LINE(E6); + #if PIN_EXISTS(E6_MS3) + PIN_CHAR(E6_MS3); + #endif #endif #if HAS_E7_MS_PINS - SERIAL_ECHOPGM("E7: "); - SERIAL_CHAR('0' + READ(E7_MS1_PIN), '0' + READ(E7_MS2_PIN) - #if PIN_EXISTS(E7_MS3) - , '0' + READ(E7_MS3_PIN) - #endif - ); + MS_LINE(E7); + #if PIN_EXISTS(E7_MS3) + PIN_CHAR(E7_MS3); + #endif #endif + SERIAL_EOL(); } #endif // HAS_MICROSTEPS From 2e03c7939ca351431c5c6bc727d71d8b8f7eb374 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 04:42:01 -0500 Subject: [PATCH 0468/1454] Simplification --- Marlin/src/module/stepper.h | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index a89d36e98f..38af36db51 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -452,11 +452,7 @@ class Stepper { // The extruder associated to the last movement FORCE_INLINE static uint8_t movement_extruder() { - return (0 - #if EXTRUDERS > 1 && DISABLED(MIXING_EXTRUDER) - + last_moved_extruder - #endif - ); + return (EXTRUDERS > 1 && DISABLED(MIXING_EXTRUDER)) ? last_moved_extruder : 0; } // Handle a triggered endstop From b88cf2edcb306d2878c233361cdac27c2a293b96 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 14:46:14 -0500 Subject: [PATCH 0469/1454] Remove version appendage --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c2788603fa..2d4a8e9b5c 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -34,7 +34,7 @@ * Verbose version identifier which should contain a reference to the location * from where the binary was downloaded or the source code was compiled. */ -//#define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION " (Github)" +//#define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION /** * The STRING_DISTRIBUTION_DATE represents when the binary file was built, diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 685fcbc25d..81731acaec 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -33,7 +33,7 @@ * vendor name, download location, GitHub account, etc. */ #ifndef DETAILED_BUILD_VERSION - #define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION " (GitHub)" + #define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION #endif /** From 18a01f2c40410e40a357fb9a1e5333d0771908e7 Mon Sep 17 00:00:00 2001 From: chestwood96 Date: Tue, 12 May 2020 21:57:18 +0200 Subject: [PATCH 0470/1454] Add user's build (_date_ _time_) to M115 output (#17957) Co-authored-by: Scott Lahteine --- Marlin/src/core/language.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index d7b50a52ce..bc81f78cd3 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -125,7 +125,7 @@ #define STR_INVALID_E_STEPPER "Invalid E stepper" #define STR_E_STEPPER_NOT_SPECIFIED "E stepper not specified" #define STR_INVALID_SOLENOID "Invalid solenoid" -#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID +#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID #define STR_COUNT_X " Count X:" #define STR_COUNT_A " Count A:" #define STR_WATCHDOG_FIRED "Watchdog timeout. Reset required." From 69d4bc92719da1ad62e5d07b43a95534072c274e Mon Sep 17 00:00:00 2001 From: "Zs.Antal" <45710979+AntoszHUN@users.noreply.github.com> Date: Tue, 12 May 2020 21:59:19 +0200 Subject: [PATCH 0471/1454] Fix Hungarian language (#17936) --- Marlin/src/lcd/language/language_hu.h | 103 +++++++++++++++----------- 1 file changed, 60 insertions(+), 43 deletions(-) diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index e07dd4c64e..da647de1bc 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -35,7 +35,7 @@ namespace Language_hu { using namespace Language_en; // A fordítás az örökölt Amerikai Angol (English) karakterláncokat használja. -namespace Language_hu { + constexpr uint8_t CHARSIZE = 2; PROGMEM Language_Str LANGUAGE = _UxGT("Magyar"); @@ -74,20 +74,20 @@ namespace Language_hu { PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preheat ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preheat ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Fej"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Fej ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Mind"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Ágy"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Beáll"); - PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Preheat ") PREHEAT_2_LABEL; - PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Preheat ") PREHEAT_2_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Fej"); - PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Fej ~"); - PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Mind"); - PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Ágy"); - PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Beáll"); + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Fütés ") PREHEAT_1_LABEL; + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Fütés ") PREHEAT_1_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej"); + PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej ~"); + PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Mind"); + PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Ágy"); + PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Beáll"); + PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Fütés ") PREHEAT_2_LABEL; + PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Fütés ") PREHEAT_2_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Fej"); + PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Fej ~"); + PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Mind"); + PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Ágy"); + PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Beáll"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Egyedi Elömelegítés"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Visszahütés"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); @@ -208,7 +208,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Vezérlés"); PROGMEM Language_Str MSG_LEDS = _UxGT("Világítás"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított Fény"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított Színek"); PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Piros"); PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Narancs"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Sárga"); @@ -218,7 +218,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Fehér"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni Fény"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni Szín"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros Intenzitás"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld Intenzitás"); PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Kék Intenzitás"); @@ -258,14 +258,18 @@ namespace Language_hu { PROGMEM Language_Str MSG_FLOW = _UxGT("Folyás"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Folyás ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Konfiguráció"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tény"); + PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Minimum"); + PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Maximum"); + PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tényezö"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Automata Höfok"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Be"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Ki"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Hangolás"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Hangolás *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz Adagoló."); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); @@ -280,10 +284,10 @@ namespace Language_hu { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); PROGMEM Language_Str MSG_JERK = _UxGT("Rántás"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Rántás"); + PROGMEM Language_Str MSG_VA_JERK = LCD_STR_A _UxGT(" Ránt. Seb."); + PROGMEM Language_Str MSG_VB_JERK = LCD_STR_B _UxGT(" Ránt. Seb."); + PROGMEM Language_Str MSG_VC_JERK = LCD_STR_C _UxGT(" Ránt. Seb."); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("E Ránt. Seb."); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont Eltérés"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Sebesség"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Sebesség ") LCD_STR_A; @@ -292,19 +296,21 @@ namespace Language_hu { PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Sebesség ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max Sebesség *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Min Sebesség"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Utazó.Seb."); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Utazó.seb."); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Gyorsulás"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Gyorsulás ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Gyorsulás ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Gyorsulás ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Gyorsulás ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Gyors. ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Gyors. ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Gyors. ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Gyors. ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Gyorsulás *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Szál visszahúzás"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Visszahúzás"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Utazás"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max Frekvencia"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min Elötolás"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("lépés/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("lépés/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("lépés/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" lépés/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" lépés/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" lépés/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E lépés/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*lépés/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Höfok"); @@ -318,18 +324,18 @@ namespace Language_hu { PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Haladó K"); PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Haladó K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontraszt"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Tárolás EEPROM"); + PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Mentés EEPROM"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Betöltés EEPROM"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Alapértelmezett"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM Inicializálás"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: EEPROM Index"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: EEPROM Verzió"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Hiba: EEPROM CRC"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Hiba: EEPROM Index"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Hiba: EEPROM Verzió"); PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Beállítások Mentve"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Tároló Frissítés"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Nyomtató Újraindítása"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Frissítés"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Infó Képernyö"); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT(""); PROGMEM Language_Str MSG_PREPARE = _UxGT("Vezérlés"); PROGMEM Language_Str MSG_TUNE = _UxGT("Hangolás"); PROGMEM Language_Str MSG_START_PRINT = _UxGT("Nyomtatás Indítása"); @@ -371,11 +377,22 @@ namespace Language_hu { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoVisszah."); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás Távolság"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra Csere"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási Távolság"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Szerszámcsere"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Emelés"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Fösebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Visszah. Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Fösebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Visszah. Sebesség"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Fej Parkolás"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Visszahúzás Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("FAN Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("FAN idö"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto BE"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto KI"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Szerszámcsere"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Automata Csere"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Utolsó Adagoló"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Csere *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Szál csere"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Szál csere *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Szál betöltés"); @@ -462,10 +479,10 @@ namespace Language_hu { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris Szintezés"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes Ágy Szintezés"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló Szintezés"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Nyomtató Statisztika"); + PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap Infó"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruderek"); + PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Adagolók"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Átviteli sebesség"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Futáselemzés: KI"); @@ -593,7 +610,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrid Küszöbérték"); PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Motoros Kezdöpont"); PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Léptetö Mód"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Aktív"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Mód"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Újraindítás"); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" be:"); PROGMEM Language_Str MSG_BACKLASH = _UxGT("Holtjáték"); From 27beade88884b42513b4525f79df401c18f5b991 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 16:32:29 -0500 Subject: [PATCH 0472/1454] Update EP comment --- Marlin/Configuration_adv.h | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 245b2a022f..16fe3824f0 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1792,10 +1792,14 @@ //#define SERIAL_STATS_DROPPED_RX #endif -// Enable an emergency-command parser to intercept certain commands as they -// enter the serial receive buffer, so they cannot be blocked. -// Currently handles M108, M112, M410 -// Does not work on boards using AT90USB (USBCON), ESP32, STM32F1/4/7, or Teensy 3.5/3.6 processors! +/** + * Emergency Command Parser + * + * Add a low-level parser to intercept certain commands as they + * enter the serial receive buffer, so they cannot be blocked. + * Currently handles M108, M112, M410, M876 + * NOTE: Not yet implemented for all platforms. + */ //#define EMERGENCY_PARSER // Bad Serial-connections can miss a received command by sending an 'ok' From 104d0202225d9ff65f289e363e27b712012ec91e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 13 May 2020 00:04:03 +0000 Subject: [PATCH 0473/1454] [cron] Bump distribution date (2020-05-13) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 81731acaec..84ae351cc4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-12" + #define STRING_DISTRIBUTION_DATE "2020-05-13" #endif /** From 6d92f5658219d5aa3a121300319836106166ca74 Mon Sep 17 00:00:00 2001 From: Gustavo Alvarez <462213+sl1pkn07@users.noreply.github.com> Date: Wed, 13 May 2020 21:22:03 +0200 Subject: [PATCH 0474/1454] FTDI/EVE, pins cleanup for SKR E3/DIP (#17990) --- Marlin/Configuration_adv.h | 2 - .../lib/ftdi_eve_touch_ui/pin_mappings.h | 9 --- Marlin/src/pins/ramps/pins_RAMPS.h | 7 +-- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 60 ++++++++---------- .../src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 61 ++++++++----------- 5 files changed, 53 insertions(+), 86 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 16fe3824f0..7bd8e72a09 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1381,8 +1381,6 @@ //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping - //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, and Stock boards) EXP1 pin mapping - //#define GENERIC_EXP2_PINMAP // GENERIC EXP2 pin mapping //#define OTHER_PIN_LAYOUT // Define pins manually below #if ENABLED(OTHER_PIN_LAYOUT) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 236ecf49c6..208210b080 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -154,12 +154,3 @@ #define CLCD_SPI_EXTRA_CS SDSS #endif #endif - -#if EITHER(E3_EXP1_PINMAP, GENERIC_EXP2_PINMAP) - #ifndef __MARLIN_FIRMWARE__ - #error "This pin mapping requires Marlin." - #endif - - #define CLCD_MOD_RESET BTN_EN1 - #define CLCD_SPI_CS LCD_PINS_RS -#endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 4ba2628b09..aed2e93d0a 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -759,11 +759,8 @@ #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define LCD_PINS_RS 33 - #define SD_DETECT_PIN 49 - #define KILL_PIN -1 - + #define CLCD_MOD_RESET 31 + #define CLCD_SPI_CS 33 #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index d7c677e3ff..7dbd62accf 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -172,39 +172,31 @@ * EXP1 */ -#define EXPA1_03_PIN PB7 -#define EXPA1_04_PIN PB8 -#define EXPA1_05_PIN PB9 -#define EXPA1_06_PIN PA10 -#define EXPA1_07_PIN -1 -#define EXPA1_08_PIN PA9 -#define EXPA1_09_PIN PB6 -#define EXPA1_10_PIN PA15 #if HAS_SPI_LCD #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN PA15 - #define BTN_ENC EXPA1_09_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC PB6 + #define BTN_EN1 PA9 + #define BTN_EN2 PA10 - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PB7 + #define LCD_PINS_D4 PB9 #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." - #define LCD_PINS_RS EXPA1_05_PIN - #define LCD_PINS_ENABLE EXPA1_09_PIN - #define LCD_PINS_D4 EXPA1_04_PIN - #define LCD_PINS_D5 EXPA1_06_PIN - #define LCD_PINS_D6 EXPA1_08_PIN - #define LCD_PINS_D7 EXPA1_10_PIN + #define LCD_PINS_RS PB9 + #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_D4 PB8 + #define LCD_PINS_D5 PA10 + #define LCD_PINS_D6 PA9 + #define LCD_PINS_D7 PA15 #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) @@ -220,14 +212,14 @@ * EXP1 */ - #define BTN_ENC EXPA1_09_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC PB6 + #define BTN_EN1 PA9 + #define BTN_EN2 PA10 - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_CS PB8 + #define DOGLCD_A0 PB9 + #define DOGLCD_SCK PA15 + #define DOGLCD_MOSI PB7 #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -272,10 +264,10 @@ #define CLCD_SPI_BUS 1 // SPI1 connector - #define BEEPER_PIN EXPA1_09_PIN + #define BEEPER_PIN PB6 - #define BTN_EN1 EXPA1_08_PIN - #define LCD_PINS_RS EXPA1_04_PIN + #define CLCD_MOD_RESET PA9 + #define CLCD_SPI_CS PA8 #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 @@ -284,7 +276,7 @@ // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) @@ -292,8 +284,8 @@ #endif #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) && SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN EXPA1_10_PIN - #define SS_PIN EXPA1_06_PIN + #define SD_DETECT_PIN PA15 + #define SS_PIN PA10 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR E3 DIP." #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index a8c295c134..30963b9879 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -112,39 +112,30 @@ * EXP1 */ -#define EXPA1_03_PIN PB7 -#define EXPA1_04_PIN PB8 -#define EXPA1_05_PIN PB9 -#define EXPA1_06_PIN PA10 -#define EXPA1_07_PIN -1 -#define EXPA1_08_PIN PA9 -#define EXPA1_09_PIN PB6 -#define EXPA1_10_PIN PB5 - #if HAS_SPI_LCD #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN PB5 - #define BTN_ENC EXPA1_09_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC PB6 + #define BTN_EN1 PA9 + #define BTN_EN2 PA10 - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE PB7 + #define LCD_PINS_D4 PB9 #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." - #define LCD_PINS_RS EXPA1_05_PIN - #define LCD_PINS_ENABLE EXPA1_09_PIN - #define LCD_PINS_D4 EXPA1_04_PIN - #define LCD_PINS_D5 EXPA1_06_PIN - #define LCD_PINS_D6 EXPA1_08_PIN - #define LCD_PINS_D7 EXPA1_10_PIN + #define LCD_PINS_RS PB9 + #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_D4 PB8 + #define LCD_PINS_D5 PA10 + #define LCD_PINS_D6 PA9 + #define LCD_PINS_D7 PB5 #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) @@ -160,14 +151,14 @@ * EXP1 */ - #define BTN_ENC EXPA1_09_PIN - #define BTN_EN1 EXPA1_08_PIN - #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC PB6 + #define BTN_EN1 PA9 + #define BTN_EN2 PA10 - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_A0 EXPA1_05_PIN - #define DOGLCD_SCK EXPA1_10_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_CS PB8 + #define DOGLCD_A0 PB9 + #define DOGLCD_SCK PB5 + #define DOGLCD_MOSI PB7 #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -212,12 +203,10 @@ #define CLCD_SPI_BUS 1 // SPI1 connector - #define BEEPER_PIN EXPA1_09_PIN + #define BEEPER_PIN PB6 - #define BTN_EN1 EXPA1_08_PIN - #define LCD_PINS_RS EXPA1_04_PIN - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define CLCD_MOD_RESET PA9 + #define CLCD_SPI_CS PB8 #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 @@ -234,8 +223,8 @@ #endif #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) && SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN EXPA1_10_PIN - #define SS_PIN EXPA1_06_PIN + #define SD_DETECT_PIN PB5 + #define SS_PIN PA10 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." #endif From 21bfb94357d171361c30fd6411932436e8c23d58 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 13 May 2020 12:22:41 -0700 Subject: [PATCH 0475/1454] Fix FTDI EVE Touch UI typo (#17985) --- .../src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp index ae0462683d..bd6653394d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp @@ -57,7 +57,7 @@ void TuneMenu::onRedraw(draw_mode_t what) { #define PAUSE_POS BTN_POS(1,3), BTN_SIZE(1,1) #define STOP_POS BTN_POS(2,3), BTN_SIZE(1,1) #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) - #defome BACK_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(2,4), BTN_SIZE(1,1) #endif if (what & FOREGROUND) { From 5a92462c0fa8fdd84ea315c62c89f5fed0978224 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 13 May 2020 12:26:27 -0700 Subject: [PATCH 0476/1454] Less ambiguous option comment (#17983) --- Marlin/Configuration_adv.h | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7bd8e72a09..8bf46d5364 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1978,7 +1978,7 @@ #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change. //#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change. - //#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change + //#define HOME_BEFORE_FILAMENT_CHANGE // If needed, home before parking for filament change //#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu. //#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302) diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 6c351daf79..815fb8078d 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -97,7 +97,7 @@ void GcodeSuite::M600() { #endif #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) - // Don't allow filament change without homing first + // If needed, home before parking for filament change if (!all_axes_known()) home_all_axes(); #endif From 6ec89031ee192c20659fb6d274c9ad7fa890451d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 13 May 2020 15:36:25 -0500 Subject: [PATCH 0477/1454] Fix BIGTREE_SKR_PRO tests --- buildroot/share/tests/BIGTREE_SKR_PRO-tests | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/share/tests/BIGTREE_SKR_PRO-tests b/buildroot/share/tests/BIGTREE_SKR_PRO-tests index 1617275de9..1295f5858c 100644 --- a/buildroot/share/tests/BIGTREE_SKR_PRO-tests +++ b/buildroot/share/tests/BIGTREE_SKR_PRO-tests @@ -23,10 +23,10 @@ opt_set TEMP_SENSOR_2 1 opt_set E0_AUTO_FAN_PIN PC10 opt_set E1_AUTO_FAN_PIN PC11 opt_set E2_AUTO_FAN_PIN PC12 -opt_set BLTOUCH Z_SAFE_HOMING opt_set X_DRIVER_TYPE TMC2209 opt_set Y_DRIVER_TYPE TMC2130 -exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders, Auto-Fan, BLTOUCH, and mixed TMC drivers" +opt_enable BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING +exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders, Auto-Fan, BLTOUCH, mixed TMC drivers" # clean up restore_configs From 1d654b559db77e866351d1bb18bf227af8d87bd7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 14 May 2020 00:03:58 +0000 Subject: [PATCH 0478/1454] [cron] Bump distribution date (2020-05-14) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 84ae351cc4..147bbf864a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-13" + #define STRING_DISTRIBUTION_DATE "2020-05-14" #endif /** From 6ae7a40f994ffb2d2be10a041bdfe89f4585db91 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 14 May 2020 13:00:47 -0500 Subject: [PATCH 0479/1454] CoreXY sensorless homing (#17972) --- Marlin/src/inc/Conditionals_post.h | 9 +++++++++ Marlin/src/module/endstops.cpp | 27 +++++++++++++++++++++++---- buildroot/share/tests/teensy35-tests | 5 +++-- 3 files changed, 35 insertions(+), 6 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 7d5cb060b9..70601c3158 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1587,6 +1587,15 @@ #if _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif +#if _HAS_STOP(X,STOP) + #define HAS_X_STOP 1 +#endif +#if _HAS_STOP(Y,STOP) + #define HAS_Y_STOP 1 +#endif +#if _HAS_STOP(Z,STOP) + #define HAS_Z_STOP 1 +#endif #if PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 092043b59c..5cfd7771a0 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -742,7 +742,8 @@ void Endstops::update() { } #endif - // Now, we must signal, after validation, if an endstop limit is pressed or not + // Signal, after validation, if an endstop limit is pressed or not + if (stepper.axis_is_moving(X_AXIS)) { if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_DIR < 0) @@ -804,19 +805,37 @@ void Endstops::update() { bool Endstops::tmc_spi_homing_check() { bool hit = false; #if X_SPI_SENSORLESS - if (tmc_spi_homing.x && stepperX.test_stall_status()) { + if (tmc_spi_homing.x && (stepperX.test_stall_status() + #if CORE_IS_XY && Y_SPI_SENSORLESS + || stepperY.test_stall_status() + #elif CORE_IS_XZ && Z_SPI_SENSORLESS + || stepperZ.test_stall_status() + #endif + )) { SBI(live_state, X_STOP); hit = true; } #endif #if Y_SPI_SENSORLESS - if (tmc_spi_homing.y && stepperY.test_stall_status()) { + if (tmc_spi_homing.y && (stepperY.test_stall_status() + #if CORE_IS_XY && X_SPI_SENSORLESS + || stepperX.test_stall_status() + #elif CORE_IS_YZ && Z_SPI_SENSORLESS + || stepperZ.test_stall_status() + #endif + )) { SBI(live_state, Y_STOP); hit = true; } #endif #if Z_SPI_SENSORLESS - if (tmc_spi_homing.z && stepperZ.test_stall_status()) { + if (tmc_spi_homing.z && (stepperZ.test_stall_status() + #if CORE_IS_XZ && X_SPI_SENSORLESS + || stepperX.test_stall_status() + #elif CORE_IS_YZ && Y_SPI_SENSORLESS + || stepperY.test_stall_status() + #endif + )) { SBI(live_state, Z_STOP); hit = true; } diff --git a/buildroot/share/tests/teensy35-tests b/buildroot/share/tests/teensy35-tests index f2a098e7cd..6ea8bd3c1c 100755 --- a/buildroot/share/tests/teensy35-tests +++ b/buildroot/share/tests/teensy35-tests @@ -83,13 +83,14 @@ exec_test $1 $2 "Mixing Extruder" # opt_set NUM_SERVOS 1 # opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER # exec_test $1 $2 "SWITCHING_EXTRUDER" + # # Enable COREXY # restore_configs opt_set MOTHERBOARD BOARD_TEENSY35_36 opt_enable COREXY -exec_test $1 $2 "COREXY" +exec_test $1 $2 "Teensy 3.5/3.6 COREXY" # # Enable COREXZ @@ -97,7 +98,7 @@ exec_test $1 $2 "COREXY" restore_configs opt_set MOTHERBOARD BOARD_TEENSY35_36 opt_enable COREXZ -exec_test $1 $2 "COREXZ" +exec_test $1 $2 "Teensy 3.5/3.6 COREXZ" # # Enable Dual Z with Dual Z endstops From 64876f77817bc768f5e26b0d2ff1268f35c88b91 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 15 May 2020 00:04:02 +0000 Subject: [PATCH 0480/1454] [cron] Bump distribution date (2020-05-15) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 147bbf864a..23bc09030e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-14" + #define STRING_DISTRIBUTION_DATE "2020-05-15" #endif /** From 3e739937346565a9ee1f79638dfe9f047316c036 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 16 May 2020 00:04:08 +0000 Subject: [PATCH 0481/1454] [cron] Bump distribution date (2020-05-16) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 23bc09030e..99950c991b 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-15" + #define STRING_DISTRIBUTION_DATE "2020-05-16" #endif /** From 76a65ffe7417eaa15e16bde825d36ac11a5ea56b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mika=20Nor=C3=A9n?= <33817034+SysGh-st@users.noreply.github.com> Date: Sat, 16 May 2020 04:11:28 +0200 Subject: [PATCH 0482/1454] Vertex nano with board K8600 (#17736) --- Marlin/src/core/boards.h | 99 +++++++++++----------- Marlin/src/pins/pins.h | 2 + Marlin/src/pins/ramps/pins_K8600.h | 127 +++++++++++++++++++++++++++++ 3 files changed, 179 insertions(+), 49 deletions(-) create mode 100644 Marlin/src/pins/ramps/pins_K8600.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 826dc51d79..aa6c7162cf 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -56,55 +56,56 @@ #define BOARD_3DRAG 1100 // 3Drag Controller #define BOARD_K8200 1101 // Velleman K8200 Controller (derived from 3Drag Controller) #define BOARD_K8400 1102 // Velleman K8400 Controller (derived from 3Drag Controller) -#define BOARD_BAM_DICE 1103 // 2PrintBeta BAM&DICE with STK drivers -#define BOARD_BAM_DICE_DUE 1104 // 2PrintBeta BAM&DICE Due with STK drivers -#define BOARD_MKS_BASE 1105 // MKS BASE v1.0 -#define BOARD_MKS_BASE_14 1106 // MKS BASE v1.4 with Allegro A4982 stepper drivers -#define BOARD_MKS_BASE_15 1107 // MKS BASE v1.5 with Allegro A4982 stepper drivers -#define BOARD_MKS_BASE_16 1108 // MKS BASE v1.6 with Allegro A4982 stepper drivers -#define BOARD_MKS_BASE_HEROIC 1109 // MKS BASE 1.0 with Heroic HR4982 stepper drivers -#define BOARD_MKS_GEN_13 1110 // MKS GEN v1.3 or 1.4 -#define BOARD_MKS_GEN_L 1111 // MKS GEN L -#define BOARD_KFB_2 1112 // BigTreeTech or BIQU KFB2.0 -#define BOARD_ZRIB_V20 1113 // zrib V2.0 control board (Chinese knock off RAMPS replica) -#define BOARD_FELIX2 1114 // Felix 2.0+ Electronics Board (RAMPS like) -#define BOARD_RIGIDBOARD 1115 // Invent-A-Part RigidBoard -#define BOARD_RIGIDBOARD_V2 1116 // Invent-A-Part RigidBoard V2 -#define BOARD_SAINSMART_2IN1 1117 // Sainsmart 2-in-1 board -#define BOARD_ULTIMAKER 1118 // Ultimaker -#define BOARD_ULTIMAKER_OLD 1119 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) -#define BOARD_AZTEEG_X3 1120 // Azteeg X3 -#define BOARD_AZTEEG_X3_PRO 1121 // Azteeg X3 Pro -#define BOARD_ULTIMAIN_2 1122 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) -#define BOARD_RUMBA 1123 // Rumba -#define BOARD_RUMBA_RAISE3D 1124 // Raise3D N series Rumba derivative -#define BOARD_RL200 1125 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) -#define BOARD_FORMBOT_TREX2PLUS 1126 // Formbot T-Rex 2 Plus -#define BOARD_FORMBOT_TREX3 1127 // Formbot T-Rex 3 -#define BOARD_FORMBOT_RAPTOR 1128 // Formbot Raptor -#define BOARD_FORMBOT_RAPTOR2 1129 // Formbot Raptor 2 -#define BOARD_BQ_ZUM_MEGA_3D 1130 // bq ZUM Mega 3D -#define BOARD_MAKEBOARD_MINI 1131 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake -#define BOARD_TRIGORILLA_13 1132 // TriGorilla Anycubic version 1.3-based on RAMPS EFB -#define BOARD_TRIGORILLA_14 1133 // ... Ver 1.4 -#define BOARD_TRIGORILLA_14_11 1134 // ... Rev 1.1 (new servo pin order) -#define BOARD_RAMPS_ENDER_4 1135 // Creality: Ender-4, CR-8 -#define BOARD_RAMPS_CREALITY 1136 // Creality: CR10S, CR20, CR-X -#define BOARD_RAMPS_DAGOMA 1137 // Dagoma F5 -#define BOARD_FYSETC_F6_13 1138 // FYSETC F6 1.3 -#define BOARD_FYSETC_F6_14 1139 // FYSETC F6 1.4 -#define BOARD_DUPLICATOR_I3_PLUS 1140 // Wanhao Duplicator i3 Plus -#define BOARD_VORON 1141 // VORON Design -#define BOARD_TRONXY_V3_1_0 1142 // Tronxy TRONXY-V3-1.0 -#define BOARD_Z_BOLT_X_SERIES 1143 // Z-Bolt X Series -#define BOARD_TT_OSCAR 1144 // TT OSCAR -#define BOARD_OVERLORD 1145 // Overlord/Overlord Pro -#define BOARD_HJC2560C_REV1 1146 // ADIMLab Gantry v1 -#define BOARD_HJC2560C_REV2 1147 // ADIMLab Gantry v2 -#define BOARD_TANGO 1148 // BIQU Tango V1 -#define BOARD_MKS_GEN_L_V2 1149 // MKS GEN L V2 -#define BOARD_COPYMASTER_3D 1150 // Copymaster 3D -#define BOARD_ORTUR_4 1151 // Ortur 4 +#define BOARD_K8600 1103 // Velleman K8600 Controller (Vertex Nano) +#define BOARD_BAM_DICE 1104 // 2PrintBeta BAM&DICE with STK drivers +#define BOARD_BAM_DICE_DUE 1105 // 2PrintBeta BAM&DICE Due with STK drivers +#define BOARD_MKS_BASE 1106 // MKS BASE v1.0 +#define BOARD_MKS_BASE_14 1107 // MKS BASE v1.4 with Allegro A4982 stepper drivers +#define BOARD_MKS_BASE_15 1108 // MKS BASE v1.5 with Allegro A4982 stepper drivers +#define BOARD_MKS_BASE_16 1109 // MKS BASE v1.6 with Allegro A4982 stepper drivers +#define BOARD_MKS_BASE_HEROIC 1110 // MKS BASE 1.0 with Heroic HR4982 stepper drivers +#define BOARD_MKS_GEN_13 1111 // MKS GEN v1.3 or 1.4 +#define BOARD_MKS_GEN_L 1112 // MKS GEN L +#define BOARD_KFB_2 1113 // BigTreeTech or BIQU KFB2.0 +#define BOARD_ZRIB_V20 1114 // zrib V2.0 control board (Chinese knock off RAMPS replica) +#define BOARD_FELIX2 1115 // Felix 2.0+ Electronics Board (RAMPS like) +#define BOARD_RIGIDBOARD 1116 // Invent-A-Part RigidBoard +#define BOARD_RIGIDBOARD_V2 1117 // Invent-A-Part RigidBoard V2 +#define BOARD_SAINSMART_2IN1 1118 // Sainsmart 2-in-1 board +#define BOARD_ULTIMAKER 1119 // Ultimaker +#define BOARD_ULTIMAKER_OLD 1120 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) +#define BOARD_AZTEEG_X3 1121 // Azteeg X3 +#define BOARD_AZTEEG_X3_PRO 1122 // Azteeg X3 Pro +#define BOARD_ULTIMAIN_2 1123 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) +#define BOARD_RUMBA 1124 // Rumba +#define BOARD_RUMBA_RAISE3D 1125 // Raise3D N series Rumba derivative +#define BOARD_RL200 1126 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) +#define BOARD_FORMBOT_TREX2PLUS 1127 // Formbot T-Rex 2 Plus +#define BOARD_FORMBOT_TREX3 1128 // Formbot T-Rex 3 +#define BOARD_FORMBOT_RAPTOR 1129 // Formbot Raptor +#define BOARD_FORMBOT_RAPTOR2 1130 // Formbot Raptor 2 +#define BOARD_BQ_ZUM_MEGA_3D 1131 // bq ZUM Mega 3D +#define BOARD_MAKEBOARD_MINI 1132 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake +#define BOARD_TRIGORILLA_13 1133 // TriGorilla Anycubic version 1.3-based on RAMPS EFB +#define BOARD_TRIGORILLA_14 1134 // ... Ver 1.4 +#define BOARD_TRIGORILLA_14_11 1135 // ... Rev 1.1 (new servo pin order) +#define BOARD_RAMPS_ENDER_4 1136 // Creality: Ender-4, CR-8 +#define BOARD_RAMPS_CREALITY 1137 // Creality: CR10S, CR20, CR-X +#define BOARD_RAMPS_DAGOMA 1138 // Dagoma F5 +#define BOARD_FYSETC_F6_13 1139 // FYSETC F6 1.3 +#define BOARD_FYSETC_F6_14 1140 // FYSETC F6 1.4 +#define BOARD_DUPLICATOR_I3_PLUS 1141 // Wanhao Duplicator i3 Plus +#define BOARD_VORON 1142 // VORON Design +#define BOARD_TRONXY_V3_1_0 1143 // Tronxy TRONXY-V3-1.0 +#define BOARD_Z_BOLT_X_SERIES 1144 // Z-Bolt X Series +#define BOARD_TT_OSCAR 1145 // TT OSCAR +#define BOARD_OVERLORD 1146 // Overlord/Overlord Pro +#define BOARD_HJC2560C_REV1 1147 // ADIMLab Gantry v1 +#define BOARD_HJC2560C_REV2 1148 // ADIMLab Gantry v2 +#define BOARD_TANGO 1149 // BIQU Tango V1 +#define BOARD_MKS_GEN_L_V2 1150 // MKS GEN L V2 +#define BOARD_COPYMASTER_3D 1151 // Copymaster 3D +#define BOARD_ORTUR_4 1152 // Ortur 4 // // RAMBo and derivatives diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 3ce761c6cf..3dc7a67593 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -98,6 +98,8 @@ #include "ramps/pins_K8200.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) #elif MB(K8400) #include "ramps/pins_K8400.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) +#elif MB(K8600) + #include "ramps/pins_K8600.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(K8800) #include "ramps/pins_K8800.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) #elif MB(BAM_DICE) diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h new file mode 100644 index 0000000000..17c230fe32 --- /dev/null +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -0,0 +1,127 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * VERTEX NANO Arduino Mega with RAMPS EFB v1.4 pin assignments. + */ + +#if HOTENDS > 1 + #error "Only 1 hotend is supported for Vertex Nano." +#endif + +#define BOARD_INFO_NAME "K8600" +#define DEFAULT_MACHINE_NAME "Vertex Nano" + +// +// Limit Switches +// +#define X_MIN_PIN 3 +#define Y_MAX_PIN 14 +#define Z_MAX_PIN 18 +#define Z_MIN_PIN -1 + +// +// Heaters / Fans +// +#define FAN_PIN 8 + +// +// Misc. Functions +// +#define CASE_LIGHT_PIN 7 + +// +// Other RAMPS pins +// +#define IS_RAMPS_EFB // Override autodetection. Bed will be undefined. +#include "pins_RAMPS.h" + +// +// Steppers +// +#undef X_STEP_PIN +#undef X_DIR_PIN +#undef X_ENABLE_PIN +#define X_STEP_PIN 54 +#define X_DIR_PIN 55 +#define X_ENABLE_PIN 38 + +#undef Y_STEP_PIN +#undef Y_DIR_PIN +#undef Y_ENABLE_PIN +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 + +#undef Z_ENABLE_PIN +#define Z_ENABLE_PIN 63 + +#undef E0_STEP_PIN +#undef E0_DIR_PIN +#undef E0_ENABLE_PIN +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 24 + +// +// Heaters / Fans +// +#undef HEATER_BED_PIN + +// +// Misc. Functions +// +#undef SDSS +#define SDSS 25 // 53 + +// +// LCD / Controller +// +#if BOTH(ULTRA_LCD, NEWPANEL) + #undef BEEPER_PIN + + #undef LCD_PINS_RS + #undef LCD_PINS_ENABLE + #undef LCD_PINS_D4 + #undef LCD_PINS_D5 + #undef LCD_PINS_D6 + #undef LCD_PINS_D7 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 37 + #define LCD_PINS_D5 35 + #define LCD_PINS_D6 33 + #define LCD_PINS_D7 31 + + // Buttons + #undef BTN_EN1 + #undef BTN_EN2 + #undef BTN_ENC + #define BTN_EN1 17 + #define BTN_EN2 16 + #define BTN_ENC 23 + +#else + + #define BEEPER_PIN 33 + +#endif From 45a01a3ecab5247826c8d1cb3d7b531724d774e7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 May 2020 01:06:18 -0500 Subject: [PATCH 0483/1454] Non-SPI core homing pin tests (#17996) --- Marlin/src/module/endstops.cpp | 63 ++++++++++++++++++++++++++++ buildroot/share/tests/teensy35-tests | 7 ++++ 2 files changed, 70 insertions(+) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 5cfd7771a0..47d63df64b 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -674,6 +674,15 @@ void Endstops::update() { } \ }while(0) + // Core Sensorless Homing needs to test an Extra Pin + #define CORE_DIAG(QQ,A,MM) (CORE_IS_##QQ && A##_SENSORLESS && !A##_SPI_SENSORLESS && HAS_##A##_##MM) + #define PROCESS_CORE_ENDSTOP(A1,M1,A2,M2) do { \ + if (TEST_ENDSTOP(_ENDSTOP(A1,M1))) { \ + _ENDSTOP_HIT(A2,M2); \ + planner.endstop_triggered(_AXIS(A2)); \ + } \ + }while(0) + // Call the endstop triggered routine for dual endstops #define PROCESS_DUAL_ENDSTOP(A, MINMAX) do { \ const byte dual_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1); \ @@ -748,11 +757,29 @@ void Endstops::update() { if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_DIR < 0) PROCESS_ENDSTOP_X(MIN); + #if CORE_DIAG(XY, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,X,MIN); + #elif CORE_DIAG(XY, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,X,MIN); + #elif CORE_DIAG(XZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,X,MIN); + #elif CORE_DIAG(XZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,X,MIN); + #endif #endif } else { // +direction #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_DIR > 0) PROCESS_ENDSTOP_X(MAX); + #if CORE_DIAG(XY, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,X,MAX); + #elif CORE_DIAG(XY, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,X,MAX); + #elif CORE_DIAG(XZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,X,MAX); + #elif CORE_DIAG(XZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,X,MAX); + #endif #endif } } @@ -761,11 +788,29 @@ void Endstops::update() { if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_DIR < 0) PROCESS_ENDSTOP_Y(MIN); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #endif #endif } else { // +direction #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_DIR > 0) PROCESS_ENDSTOP_Y(MAX); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + #endif #endif } } @@ -777,6 +822,15 @@ void Endstops::update() { if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) ) PROCESS_ENDSTOP_Z(MIN); + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #endif #endif // When closing the gap check the enabled probe @@ -791,6 +845,15 @@ void Endstops::update() { #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX PROCESS_ENDSTOP(Z, MAX); #endif + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + #endif #endif } } diff --git a/buildroot/share/tests/teensy35-tests b/buildroot/share/tests/teensy35-tests index 6ea8bd3c1c..c729f212a4 100755 --- a/buildroot/share/tests/teensy35-tests +++ b/buildroot/share/tests/teensy35-tests @@ -90,6 +90,13 @@ exec_test $1 $2 "Mixing Extruder" restore_configs opt_set MOTHERBOARD BOARD_TEENSY35_36 opt_enable COREXY +opt_set X_DRIVER_TYPE TMC5160 +opt_set Y_DRIVER_TYPE TMC5160 +opt_set X_MIN_ENDSTOP_INVERTING true +opt_set Y_MIN_ENDSTOP_INVERTING true +opt_add X_CS_PIN 46 +opt_add Y_CS_PIN 47 +opt_enable USE_ZMIN_PLUG MONITOR_DRIVER_STATUS SENSORLESS_HOMING exec_test $1 $2 "Teensy 3.5/3.6 COREXY" # From 847bdeecafd14ea611af0bda723ebe99c8d2d29b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 May 2020 06:02:02 -0500 Subject: [PATCH 0484/1454] BOARD_NAME => BOARD_INFO_NAME --- Marlin/src/pins/mega/pins_PICA.h | 4 ++-- Marlin/src/pins/ramps/pins_FYSETC_F6_14.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h | 2 +- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index f00d817d6e..506ce242c5 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -29,8 +29,8 @@ * Applies to PICA, PICA_REVB */ -#ifndef BOARD_NAME - #define BOARD_NAME "PICA" +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "PICA" #endif /* diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h index f0eb0bf4c6..0597e23a16 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h @@ -25,7 +25,7 @@ // FYSETC F6 v1.4 pin assignments // -#define BOARD_NAME "FYSETC F6 1.4" +#define BOARD_INFO_NAME "FYSETC F6 1.4" #define Z_MAX_PIN 2 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 8d7687f520..5dbffd2897 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -30,7 +30,7 @@ #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif -#define BOARD_NAME "GTM32 Pro VB" +#define BOARD_INFO_NAME "GTM32 Pro VB" #define DEFAULT_MACHINE_NAME "M201" //#define DISABLE_DEBUG diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h index 36298d05f5..0aa6f709f6 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h @@ -28,7 +28,7 @@ #endif #ifndef BOARD_INFO_NAME - #define BOARD_NAME "MKS_ROBIN2" + #define BOARD_INFO_NAME "MKS_ROBIN2" #endif #ifndef DEFAULT_MACHINE_NAME diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 4d27910c16..08f8adebc4 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -28,7 +28,7 @@ #endif #define DEFAULT_MACHINE_NAME "STM32F446VET6" -#define BOARD_NAME "STM32F4 VAkE" +#define BOARD_INFO_NAME "STM32F4 VAkE" //#define I2C_EEPROM From 3de1421d72b25003f253c76f3dc5a8d2d44accaa Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 17 May 2020 00:04:07 +0000 Subject: [PATCH 0485/1454] [cron] Bump distribution date (2020-05-17) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 99950c991b..f519740dab 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-16" + #define STRING_DISTRIBUTION_DATE "2020-05-17" #endif /** From df04a427f340ef4950dd5d02cfacdfdda35e17f2 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 17 May 2020 12:48:07 -0700 Subject: [PATCH 0486/1454] Fix BTT002 SPEAKER timer conflict (#18011) --- .../share/PlatformIO/variants/BIGTREE_BTT002/variant.h | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h index ca56b5f456..ecc319f47c 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h +++ b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/variant.h @@ -245,11 +245,9 @@ extern "C" { // Timer Definitions //Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c -#define TIMER_TONE TIM6 -#define TIMER_SERIAL TIM7 - -// Do not use basic timer: OC is required -#define TIMER_SERVO TIM2 //TODO: advanced-control timers don't work +#define TIMER_TONE TIM7 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM2 // UART Definitions // Define here Serial instance number to map on Serial generic name From 2ec482a10263fbf6eaca7c8cbeb51d20bbe2be18 Mon Sep 17 00:00:00 2001 From: Bastien R Date: Sun, 17 May 2020 21:52:45 +0200 Subject: [PATCH 0487/1454] MMU2 Extruder Sensor support (#17886) --- Marlin/Configuration_adv.h | 22 +- Marlin/src/feature/mmu2/mmu2.cpp | 300 +++++++++++++++++++++----- Marlin/src/feature/mmu2/mmu2.h | 18 +- Marlin/src/inc/SanityCheck.h | 12 +- Marlin/src/lcd/language/language_fr.h | 11 +- 5 files changed, 289 insertions(+), 74 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 8bf46d5364..20c110ff7b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3279,7 +3279,7 @@ // This is for Prusa MK3-style extruders. Customize for your hardware. #define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0 #define MMU2_LOAD_TO_NOZZLE_SEQUENCE \ - { 7.2, 562 }, \ + { 7.2, 1145 }, \ { 14.4, 871 }, \ { 36.0, 1393 }, \ { 14.4, 871 }, \ @@ -3299,7 +3299,25 @@ { -50.0, 2000 } #endif - // Using a sensor like the MMU2S + /** + * MMU Extruder Sensor + * Add support for Prusa IR Sensor (or other) to detect that filament reach the extruder to make loading filament more reliable + * If your extruder is equipped with a filament sensor located less than 38mm from the gears you can use this feature + * During loading to the extruder, the sensor will stop the loading command when he's triggered and make a last move to load filament to the gears + * If no filament is detected, MMU2 will make more loading attemps, if finally no filament is detected, the printer will enter in runout state + */ + + //#define MMU_EXTRUDER_SENSOR + #if ENABLED(MMU_EXTRUDER_SENSOR) + #define MMU_LOADING_ATTEMPTS_NR 5 //max. number of attempts to load filament if first load fail + #endif + + /** + * Using a sensor like the MMU2S + * This mode only work if you have a MK3S extruder with sensor sensing the extruder idler mmu2s + * See https://help.prusa3d.com/en/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560, step 11 + */ + //#define PRUSA_MMU2_S_MODE #if ENABLED(PRUSA_MMU2_S_MODE) #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 6c61b714f7..2ddfd72647 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -51,8 +51,13 @@ MMU2 mmu2; #define MMU_TODELAY 100 #define MMU_TIMEOUT 10 -#define MMU_CMD_TIMEOUT 60000ul // 5min timeout for mmu commands (except P0) -#define MMU_P0_TIMEOUT 3000ul // Timeout for P0 command: 3seconds +#define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0) +#define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds + +#if ENABLED(MMU_EXTRUDER_SENSOR) + uint8_t mmu_idl_sens = 0; + static bool mmu_loading_flag = false; +#endif #define MMU_CMD_NONE 0 #define MMU_CMD_T0 0x10 @@ -79,11 +84,7 @@ MMU2 mmu2; #define MMU_CMD_F3 0x73 #define MMU_CMD_F4 0x74 -#if ENABLED(MMU2_MODE_12V) - #define MMU_REQUIRED_FW_BUILDNR 132 -#else - #define MMU_REQUIRED_FW_BUILDNR 126 -#endif +#define MMU_REQUIRED_FW_BUILDNR TERN(MMU2_MODE_12V, 132, 126) #define MMU2_NO_TOOL 99 #define MMU_BAUD 115200 @@ -99,7 +100,7 @@ int8_t MMU2::state = 0; volatile int8_t MMU2::finda = 1; volatile bool MMU2::finda_runout_valid; int16_t MMU2::version = -1, MMU2::buildnr = -1; -millis_t MMU2::last_request, MMU2::next_P0_request; +millis_t MMU2::prev_request, MMU2::prev_P0_request; char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; #if BOTH(HAS_LCD_MENU, MMU2_MENUS) @@ -159,6 +160,10 @@ uint8_t MMU2::get_current_tool() { return extruder == MMU2_NO_TOOL ? -1 : extruder; } +#if EITHER(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) + #define FILAMENT_PRESENT() (READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_INVERTING) +#endif + void MMU2::mmu_loop() { switch (state) { @@ -248,6 +253,7 @@ void MMU2::mmu_loop() { int filament = cmd - MMU_CMD_T0; DEBUG_ECHOLNPAIR("MMU <= T", filament); tx_printf_P(PSTR("T%d\n"), filament); + TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L4)) { @@ -296,7 +302,7 @@ void MMU2::mmu_loop() { last_cmd = cmd; cmd = MMU_CMD_NONE; } - else if (ELAPSED(millis(), next_P0_request)) { + else if (ELAPSED(millis(), prev_P0_request + 300)) { // read FINDA tx_str_P(PSTR("P0\n")); state = 2; // wait for response @@ -312,26 +318,35 @@ void MMU2::mmu_loop() { // This is super annoying. Only activate if necessary // if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6); - state = 1; - - if (cmd == 0) ready = true; - if (!finda && finda_runout_valid) filament_runout(); + if (cmd == 0) ready = true; + state = 1; } - else if (ELAPSED(millis(), last_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s) + else if (ELAPSED(millis(), prev_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s) state = 1; TERN_(PRUSA_MMU2_S_MODE, check_filament()); break; case 3: // response to mmu commands + #if ENABLED(MMU_EXTRUDER_SENSOR) + if (mmu_idl_sens) { + if (FILAMENT_PRESENT() && mmu_loading_flag) { + DEBUG_ECHOLNPGM("MMU <= 'A'\n"); + tx_str_P(PSTR("A\n")); // send 'abort' request + mmu_idl_sens = 0; + DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT\n"); + } + } + #endif + if (rx_ok()) { DEBUG_ECHOLNPGM("MMU => 'ok'"); ready = true; state = 1; last_cmd = MMU_CMD_NONE; } - else if (ELAPSED(millis(), last_request + MMU_CMD_TIMEOUT)) { + else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) { // resend request after timeout if (last_cmd) { DEBUG_ECHOLNPGM("MMU retry"); @@ -351,7 +366,7 @@ void MMU2::mmu_loop() { bool MMU2::rx_start() { // check for start message if (rx_str_P(PSTR("start\n"))) { - next_P0_request = millis() + 300; + prev_P0_request = millis(); return true; } return false; @@ -397,7 +412,7 @@ void MMU2::tx_str_P(const char* str) { uint8_t len = strlen_P(str); LOOP_L_N(i, len) mmuSerial.write(pgm_read_byte(str++)); rx_buffer[0] = '\0'; - last_request = millis(); + prev_request = millis(); } /** @@ -408,7 +423,7 @@ void MMU2::tx_printf_P(const char* format, int argument = -1) { uint8_t len = sprintf_P(tx_buffer, format, argument); LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]); rx_buffer[0] = '\0'; - last_request = millis(); + prev_request = millis(); } /** @@ -419,7 +434,7 @@ void MMU2::tx_printf_P(const char* format, int argument1, int argument2) { uint8_t len = sprintf_P(tx_buffer, format, argument1, argument2); LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]); rx_buffer[0] = '\0'; - last_request = millis(); + prev_request = millis(); } /** @@ -435,7 +450,7 @@ void MMU2::clear_rx_buffer() { */ bool MMU2::rx_ok() { if (rx_str_P(PSTR("ok\n"))) { - next_P0_request = millis() + 300; + prev_P0_request = millis(); return true; } return false; @@ -476,32 +491,206 @@ static bool mmu2_not_responding() { return success; } -#endif + /** + * Handle tool change + */ + void MMU2::tool_change(const uint8_t index) { + + if (!enabled) return; + + set_runout_valid(false); + + if (index != extruder) { + + DISABLE_AXIS_E0(); + ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + + command(MMU_CMD_T0 + index); + manage_response(true, true); + + if (load_to_gears()) { + extruder = index; // filament change is finished + active_extruder = 0; + ENABLE_AXIS_E0(); + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); + } + ui.reset_status(); + } + + set_runout_valid(true); + } + + /** + * Handle special T?/Tx/Tc commands + * + * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically + * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. + * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. + */ + void MMU2::tool_change(const char* special) { + + if (!enabled) return; + + #if ENABLED(MMU2_MENUS) + + set_runout_valid(false); + + switch (*special) { + case '?': { + uint8_t index = mmu2_choose_filament(); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + load_filament_to_nozzle(index); + } break; + + case 'x': { + planner.synchronize(); + uint8_t index = mmu2_choose_filament(); + DISABLE_AXIS_E0(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + + if (load_to_gears()) { + mmu_loop(); + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; + } + } break; + + case 'c': { + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); + } break; + } + + set_runout_valid(true); + + #endif // MMU2_MENUS + } + +#elif ENABLED(MMU_EXTRUDER_SENSOR) + + /** + * Handle tool change + */ + void MMU2::tool_change(const uint8_t index) { + if (!enabled) return; + + set_runout_valid(false); + + if (index != extruder) { + DISABLE_AXIS_E0(); + if (FILAMENT_PRESENT()) { + DEBUG_ECHOLNPGM("Unloading\n"); + mmu_loading_flag = false; + command(MMU_CMD_U0); + manage_response(true, true); + } + ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + mmu_loading_flag = true; + command(MMU_CMD_T0 + index); + manage_response(true, true); + mmu_continue_loading(); + command(MMU_CMD_C0); + extruder = index; + active_extruder = 0; + + ENABLE_AXIS_E0(); + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); + + ui.reset_status(); + } + + set_runout_valid(true); + } + + /** + * Handle special T?/Tx/Tc commands + * + * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically + * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. + * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. + */ + void MMU2::tool_change(const char* special) { + if (!enabled) return; + + #if ENABLED(MMU2_MENUS) + + set_runout_valid(false); + + switch (*special) { + case '?': { + DEBUG_ECHOLNPGM("case ?\n"); + uint8_t index = mmu2_choose_filament(); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + load_filament_to_nozzle(index); + } break; + + case 'x': { + DEBUG_ECHOLNPGM("case x\n"); + planner.synchronize(); + uint8_t index = mmu2_choose_filament(); + DISABLE_AXIS_E0(); + command(MMU_CMD_T0 + index); + manage_response(true, true); + mmu_continue_loading(); + command(MMU_CMD_C0); + mmu_loop(); + + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; + } break; + + case 'c': { + DEBUG_ECHOLNPGM("case c\n"); + while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); + execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); + } break; + } + + set_runout_valid(true); + + #endif // MMU2_MENUS + } + + void MMU2::mmu_continue_loading() { + for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) { + DEBUG_ECHOLNPAIR("Additional load attempt #", i); + if (FILAMENT_PRESENT()) break; + command(MMU_CMD_C0); + manage_response(true, true); + } + if (!FILAMENT_PRESENT()) { + DEBUG_ECHOLNPGM("Filament never reached sensor, runout"); + filament_runout(); + } + mmu_idl_sens = 0; + } + +#elif DISABLED(MMU_EXTRUDER_SENSOR) && DISABLED(PRUSA_MMU2_S_MODE) /** * Handle tool change */ -void MMU2::tool_change(uint8_t index) { - +void MMU2::tool_change(const uint8_t index) { if (!enabled) return; set_runout_valid(false); if (index != extruder) { - DISABLE_AXIS_E0(); ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); - command(MMU_CMD_T0 + index); manage_response(true, true); - - if (load_to_gears()) { - extruder = index; // filament change is finished - active_extruder = 0; - ENABLE_AXIS_E0(); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); - } + command(MMU_CMD_C0); + extruder = index; //filament change is finished + active_extruder = 0; + ENABLE_AXIS_E0(); + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder)); ui.reset_status(); } @@ -518,7 +707,6 @@ void MMU2::tool_change(uint8_t index) { * */ void MMU2::tool_change(const char* special) { - if (!enabled) return; #if ENABLED(MMU2_MENUS) @@ -527,27 +715,29 @@ void MMU2::tool_change(const char* special) { switch (*special) { case '?': { + DEBUG_ECHOLNPGM("case ?\n"); uint8_t index = mmu2_choose_filament(); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); load_filament_to_nozzle(index); } break; case 'x': { + DEBUG_ECHOLNPGM("case x\n"); planner.synchronize(); uint8_t index = mmu2_choose_filament(); DISABLE_AXIS_E0(); command(MMU_CMD_T0 + index); manage_response(true, true); + command(MMU_CMD_C0); + mmu_loop(); - if (load_to_gears()) { - mmu_loop(); - ENABLE_AXIS_E0(); - extruder = index; - active_extruder = 0; - } + ENABLE_AXIS_E0(); + extruder = index; + active_extruder = 0; } break; case 'c': { + DEBUG_ECHOLNPGM("case c\n"); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); } break; @@ -556,7 +746,9 @@ void MMU2::tool_change(const char* special) { set_runout_valid(true); #endif -} + } + +#endif // MMU_EXTRUDER_SENSOR /** * Set next command @@ -593,7 +785,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { bool response = false; mmu_print_saved = false; xyz_pos_t resume_position; - int16_t resume_hotend_temp; + int16_t resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); KEEPALIVE_STATE(PAUSED_FOR_USER); @@ -652,7 +844,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { } } -void MMU2::set_filament_type(uint8_t index, uint8_t filamentType) { +void MMU2::set_filament_type(const uint8_t index, const uint8_t filamentType) { if (!enabled) return; cmd_arg = filamentType; @@ -667,20 +859,21 @@ void MMU2::filament_runout() { } #if ENABLED(PRUSA_MMU2_S_MODE) + void MMU2::check_filament() { - const bool runout = READ(FIL_RUNOUT_PIN) ^ (FIL_RUNOUT_INVERTING); - if (runout && !mmu2s_triggered) { + const bool present = FILAMENT_PRESENT(); + if (present && !mmu2s_triggered) { DEBUG_ECHOLNPGM("MMU <= 'A'"); tx_str_P(PSTR("A\n")); } - mmu2s_triggered = runout; + mmu2s_triggered = present; } bool MMU2::can_load() { execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence)); int filament_detected_count = 0; - const int steps = MMU2_CAN_LOAD_RETRACT / MMU2_CAN_LOAD_INCREMENT; + const int steps = (MMU2_CAN_LOAD_RETRACT) / (MMU2_CAN_LOAD_INCREMENT); DEBUG_ECHOLNPGM("MMU can_load:"); LOOP_L_N(i, steps) { execute_extruder_sequence((const E_Step *)can_load_increment_sequence, COUNT(can_load_increment_sequence)); @@ -689,7 +882,7 @@ void MMU2::filament_runout() { if (mmu2s_triggered) ++filament_detected_count; } - if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION / MMU2_CAN_LOAD_INCREMENT)) { + if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION) / (MMU2_CAN_LOAD_INCREMENT)) { DEBUG_ECHOLNPGM(" failed."); return false; } @@ -702,7 +895,7 @@ void MMU2::filament_runout() { #if BOTH(HAS_LCD_MENU, MMU2_MENUS) // Load filament into MMU2 - void MMU2::load_filament(uint8_t index) { + void MMU2::load_filament(const uint8_t index) { if (!enabled) return; command(MMU_CMD_L0 + index); manage_response(false, false); @@ -714,7 +907,7 @@ void MMU2::filament_runout() { * Switch material and load to nozzle * */ - bool MMU2::load_filament_to_nozzle(uint8_t index) { + bool MMU2::load_filament_to_nozzle(const uint8_t index) { if (!enabled) return false; @@ -739,7 +932,6 @@ void MMU2::filament_runout() { } /** - * * Load filament to nozzle of multimaterial printer * * This function is used only only after T? (user select filament) and M600 (change filament). @@ -751,7 +943,7 @@ void MMU2::filament_runout() { execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); } - bool MMU2::eject_filament(uint8_t index, bool recover) { + bool MMU2::eject_filament(const uint8_t index, const bool recover) { if (!enabled) return false; @@ -798,9 +990,7 @@ void MMU2::filament_runout() { } /** - * - * unload from hotend and retract to MMU - * + * Unload from hotend and retract to MMU */ bool MMU2::unload() { diff --git a/Marlin/src/feature/mmu2/mmu2.h b/Marlin/src/feature/mmu2/mmu2.h index 8dd07f8847..c956139f54 100644 --- a/Marlin/src/feature/mmu2/mmu2.h +++ b/Marlin/src/feature/mmu2/mmu2.h @@ -44,24 +44,24 @@ public: static void init(); static void reset(); static void mmu_loop(); - static void tool_change(uint8_t index); + static void tool_change(const uint8_t index); static void tool_change(const char* special); static uint8_t get_current_tool(); - static void set_filament_type(uint8_t index, uint8_t type); + static void set_filament_type(const uint8_t index, const uint8_t type); #if BOTH(HAS_LCD_MENU, MMU2_MENUS) static bool unload(); static void load_filament(uint8_t); static void load_all(); - static bool load_filament_to_nozzle(uint8_t index); - static bool eject_filament(uint8_t index, bool recover); + static bool load_filament_to_nozzle(const uint8_t index); + static bool eject_filament(const uint8_t index, const bool recover); #endif private: static bool rx_str_P(const char* str); static void tx_str_P(const char* str); - static void tx_printf_P(const char* format, int argument); - static void tx_printf_P(const char* format, int argument1, int argument2); + static void tx_printf_P(const char* format, const int argument); + static void tx_printf_P(const char* format, const int argument1, const int argument2); static void clear_rx_buffer(); static bool rx_ok(); @@ -89,6 +89,10 @@ private: FORCE_INLINE static bool load_to_gears() { return true; } #endif + #if ENABLED(MMU_EXTRUDER_SENSOR) + static void mmu_continue_loading(); + #endif + static bool enabled, ready, mmu_print_saved; static uint8_t cmd, cmd_arg, last_cmd, extruder; @@ -96,7 +100,7 @@ private: static volatile int8_t finda; static volatile bool finda_runout_valid; static int16_t version, buildnr; - static millis_t last_request, next_P0_request; + static millis_t prev_request, prev_P0_request; static char rx_buffer[MMU_RX_SIZE], tx_buffer[MMU_TX_SIZE]; static inline void set_runout_valid(const bool valid) { diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c8f8907e88..da29c0ecf0 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2742,12 +2742,14 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) * Prusa MMU2 requirements */ #if ENABLED(PRUSA_MMU2) - #if DISABLED(NOZZLE_PARK_FEATURE) - #error "PRUSA_MMU2 requires NOZZLE_PARK_FEATURE." - #elif EXTRUDERS != 5 + #if EXTRUDERS != 5 #error "PRUSA_MMU2 requires EXTRUDERS = 5." - #elif ENABLED(PRUSA_MMU2_S_MODE) && DISABLED(FILAMENT_RUNOUT_SENSOR) - #error "PRUSA_MMU2_S_MODE requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." + #elif DISABLED(NOZZLE_PARK_FEATURE) + #error "PRUSA_MMU2 requires NOZZLE_PARK_FEATURE. Enable it to continue." + #elif EITHER(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) && DISABLED(FILAMENT_RUNOUT_SENSOR) + #error "PRUSA_MMU2_S_MODE or MMU_EXTRUDER_SENSOR requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." + #elif BOTH(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) + #error "Enable only one of PRUSA_MMU2_S_MODE or MMU_EXTRUDER_SENSOR." #elif DISABLED(ADVANCED_PAUSE_FEATURE) static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2."); #endif diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 3daac87a28..ee866629b3 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -476,15 +476,16 @@ namespace Language_fr { PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Echec sonde"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Trop froid"); + PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MAJ firmware MMU!!"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOISIR FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU ne répond plus"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Continuer impr."); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Reprise..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Charger filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Charger tous"); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Continuer Imp. MMU"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Reprise MMU..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Charge dans MMU"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Charger tous dans MMU"); PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Charger dans buse"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Ejecter filament"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Ejecter fil. du MMU"); PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Ejecter fil. ~"); PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Retrait filament"); PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Chargem. fil. %i..."); From b8fe3bbd6de5141d38295f0d7a4937d4ef903726 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 May 2020 21:14:04 -0500 Subject: [PATCH 0488/1454] Fix position sync on M420 S0 --- Marlin/src/gcode/bedlevel/M420.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 3effc3173b..50b2f6f158 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -84,12 +84,12 @@ void GcodeSuite::M420() { } #endif + xyz_pos_t oldpos = current_position; + // If disabling leveling do it right away // (Don't disable for just M420 or M420 V) if (seen_S && !to_enable) set_bed_leveling_enabled(false); - xyz_pos_t oldpos = current_position; - #if ENABLED(AUTO_BED_LEVELING_UBL) // L to load a mesh from the EEPROM From c73894308c37ebf0144495a2544debc25ac22713 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 May 2020 19:49:02 -0500 Subject: [PATCH 0489/1454] Tweak M114 D output --- Marlin/src/gcode/host/M114.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 8a31f248bf..389188ada8 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -179,7 +179,7 @@ report_xyze(from_steppers); const xyze_float_t diff = from_steppers - leveled; - SERIAL_ECHOPGM("Diff: "); + SERIAL_ECHOPGM("Diff: "); report_xyze(diff); } From d9593c8ed47a07bdbb56ca5ebc7009df826fd141 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 May 2020 19:48:52 -0500 Subject: [PATCH 0490/1454] Tweak mesh xy error --- Marlin/src/core/language.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index bc81f78cd3..4bd853d219 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -162,7 +162,7 @@ #define STR_ERR_MATERIAL_INDEX "M145 S out of range (0-1)" #define STR_ERR_M421_PARAMETERS "M421 incorrect parameter usage" #define STR_ERR_BAD_PLANE_MODE "G5 requires XY plane mode" -#define STR_ERR_MESH_XY "Mesh point cannot be resolved" +#define STR_ERR_MESH_XY "Mesh point out of range" #define STR_ERR_ARC_ARGS "G2/G3 bad parameters" #define STR_ERR_PROTECTED_PIN "Protected Pin" #define STR_ERR_M420_FAILED "Failed to enable Bed Leveling" From d9077e51e878fdfa690a52d8ec177b6bc61c54b4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 May 2020 20:06:54 -0500 Subject: [PATCH 0491/1454] Make M421 more versatile --- Marlin/src/gcode/bedlevel/abl/M421.cpp | 37 +++++++++++++++++--------- 1 file changed, 24 insertions(+), 13 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 74514bf417..2e46fafcd0 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -36,28 +36,39 @@ #endif /** - * M421: Set a single Mesh Bed Leveling Z coordinate + * M421: Set one or more Mesh Bed Leveling Z coordinates * * Usage: * M421 I J Z * M421 I J Q + * + * - If I is omitted, set the entire row + * - If J is omitted, set the entire column + * - If both I and J are omitted, set all */ void GcodeSuite::M421() { int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1); - const bool hasI = ix >= 0, - hasJ = iy >= 0, - hasZ = parser.seen('Z'), - hasQ = !hasZ && parser.seen('Q'); + const bool hasZ = parser.seenval('Z'), + hasQ = !hasZ && parser.seenval('Q'); - if (!hasI || !hasJ || !(hasZ || hasQ)) - SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS); - else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) - SERIAL_ERROR_MSG(STR_ERR_MESH_XY); - else { - z_values[ix][iy] = parser.value_linear_units() + (hasQ ? z_values[ix][iy] : 0); - TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); + if (hasZ || hasQ) { + if (WITHIN(ix, -1, GRID_MAX_POINTS_X - 1) && WITHIN(iy, -1, GRID_MAX_POINTS_Y - 1)) { + const float zval = parser.value_linear_units(); + uint8_t sx = ix >= 0 ? ix : 0, ex = ix >= 0 ? ix : GRID_MAX_POINTS_X - 1, + sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1; + LOOP_S_LE_N(x, sx, ex) { + LOOP_S_LE_N(y, sy, ey) { + z_values[x][y] = zval + (hasQ ? z_values[x][y] : 0); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); + } + } + TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); + } + else + SERIAL_ERROR_MSG(STR_ERR_MESH_XY); } + else + SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS); } #endif // AUTO_BED_LEVELING_BILINEAR From c60600ebb92169bdd2cb983a86d3be53b6f449b0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 18 May 2020 00:03:57 +0000 Subject: [PATCH 0492/1454] [cron] Bump distribution date (2020-05-18) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f519740dab..abe4df3286 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-17" + #define STRING_DISTRIBUTION_DATE "2020-05-18" #endif /** From fac3a7d14788d7f80112d0c6456ae460b18764b7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 17 May 2020 18:43:36 -0500 Subject: [PATCH 0493/1454] Fix ABL G29 early BLTouch deploy --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 96 ++++++++------------------- 1 file changed, 27 insertions(+), 69 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index ead70bc257..c48c693b78 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -78,11 +78,7 @@ #endif #endif -#if ENABLED(G29_RETRY_AND_RECOVER) - #define G29_RETURN(b) return b; -#else - #define G29_RETURN(b) return; -#endif +#define G29_RETURN(b) return TERN_(G29_RETRY_AND_RECOVER, b) /** * G29: Detailed Z probe, probes the bed at 3 or more points. @@ -164,11 +160,7 @@ */ G29_TYPE GcodeSuite::G29() { - #if EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) - const bool seenQ = parser.seen('Q'); - #else - constexpr bool seenQ = false; - #endif + const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen('Q'); // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -179,25 +171,12 @@ G29_TYPE GcodeSuite::G29() { log_machine_info(); } marlin_debug_flags = old_debug_flags; - #if DISABLED(PROBE_MANUALLY) - if (seenQ) G29_RETURN(false); - #endif + if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false); #endif - #if ENABLED(PROBE_MANUALLY) - const bool seenA = parser.seen('A'); - #else - constexpr bool seenA = false; - #endif - - const bool no_action = seenA || seenQ, - faux = - #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) - parser.boolval('C') - #else - no_action - #endif - ; + const bool seenA = TERN0(PROBE_MANUALLY, parser.seen('A')), + no_action = seenA || seenQ, + faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action; // Don't allow auto-leveling without homing first if (axis_unhomed_error()) G29_RETURN(false); @@ -208,11 +187,7 @@ G29_TYPE GcodeSuite::G29() { } // Define local vars 'static' for manual probing, 'auto' otherwise - #if ENABLED(PROBE_MANUALLY) - #define ABL_VAR static - #else - #define ABL_VAR - #endif + #define ABL_VAR TERN_(PROBE_MANUALLY, static) ABL_VAR int verbose_level; ABL_VAR xy_pos_t probePos; @@ -346,11 +321,7 @@ G29_TYPE GcodeSuite::G29() { G29_RETURN(false); } - dryrun = parser.boolval('D') - #if ENABLED(PROBE_MANUALLY) - || no_action - #endif - ; + dryrun = parser.boolval('D') || TERN0(PROBE_MANUALLY, no_action); #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -430,26 +401,27 @@ G29_TYPE GcodeSuite::G29() { planner.synchronize(); + if (!faux) remember_feedrate_scaling_off(); + // Disable auto bed leveling during G29. // Be formal so G29 can be done successively without G28. if (!no_action) set_bed_leveling_enabled(false); + // Deploy certain probes before starting probing #if HAS_BED_PROBE - // Deploy the probe. Probe will raise if needed. - if (probe.deploy()) { + if (ENABLED(BLTOUCH)) + do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); + else if (probe.deploy()) { set_bed_leveling_enabled(abl_should_enable); G29_RETURN(false); } #endif - if (!faux) remember_feedrate_scaling_off(); - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - #if ENABLED(PROBE_MANUALLY) - if (!no_action) - #endif - if (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start) { + if (TERN_(PROBE_MANUALLY, !no_action) + && (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start) + ) { // Reset grid to 0.0 or "not probed". (Also disables ABL) reset_bed_level(); @@ -560,8 +532,7 @@ G29_TYPE GcodeSuite::G29() { PR_INNER_VAR = abl_probe_index - (PR_OUTER_VAR * PR_INNER_END); // Probe in reverse order for every other row/column - bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_END) & 1); - + const bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_END) & 1); if (zig) PR_INNER_VAR = (PR_INNER_END - 1) - PR_INNER_VAR; probePos = probe_position_lf + gridSpacing * meshCount.asFloat(); @@ -576,19 +547,14 @@ G29_TYPE GcodeSuite::G29() { // Is there a next point to move to? if (abl_probe_index < abl_points) { _manual_goto_xy(probePos); // Can be used here too! - #if HAS_SOFTWARE_ENDSTOPS - // Disable software endstops to allow manual adjustment - // If G29 is not completed, they will not be re-enabled - soft_endstops_enabled = false; - #endif + // Disable software endstops to allow manual adjustment + // If G29 is not completed, they will not be re-enabled + TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false); G29_RETURN(false); } else { - // Leveling done! Fall through to G29 finishing code below - SERIAL_ECHOLNPGM("Grid probing done."); - // Re-enable software endstops, if needed TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state); } @@ -599,11 +565,9 @@ G29_TYPE GcodeSuite::G29() { if (abl_probe_index < abl_points) { probePos = points[abl_probe_index]; _manual_goto_xy(probePos); - #if HAS_SOFTWARE_ENDSTOPS - // Disable software endstops to allow manual adjustment - // If G29 is not completed, they will not be re-enabled - soft_endstops_enabled = false; - #endif + // Disable software endstops to allow manual adjustment + // If G29 is not completed, they will not be re-enabled + TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false); G29_RETURN(false); } else { @@ -670,10 +634,8 @@ G29_TYPE GcodeSuite::G29() { TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index); // 0... - #if IS_KINEMATIC - // Avoid probing outside the round or hexagonal area - if (!probe.can_reach(probePos)) continue; - #endif + // Avoid probing outside the round or hexagonal area + if (TERN0(IS_KINEMATIC, !probe.can_reach(probePos))) continue; if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", int(GRID_MAX_POINTS), "."); TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(GRID_MAX_POINTS))); @@ -898,11 +860,7 @@ G29_TYPE GcodeSuite::G29() { // Unapply the offset because it is going to be immediately applied // and cause compensation movement in Z - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - const float fade_scaling_factor = planner.fade_scaling_factor_for_z(current_position.z); - #else - constexpr float fade_scaling_factor = 1.0f; - #endif + const float fade_scaling_factor = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.fade_scaling_factor_for_z(current_position.z), 1); current_position.z -= fade_scaling_factor * bilinear_z_offset(current_position); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(" corrected Z:", current_position.z); From daa5bbc5ebd4127db10eef99dd450313de64c457 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 17 May 2020 18:45:30 -0500 Subject: [PATCH 0494/1454] Comment a motion function --- Marlin/src/module/motion.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 021405b4a9..673eee3a92 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -348,6 +348,11 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { #endif // IS_KINEMATIC +/** + * Do a fast or normal move to 'destination' with an optional FR. + * - Move at normal speed regardless of feedrate percentage. + * - Extrude the specified length regardless of flow percentage. + */ void _internal_move_to_destination(const feedRate_t &fr_mm_s/*=0.0f*/ #if IS_KINEMATIC , const bool is_fast/*=false*/ @@ -360,8 +365,8 @@ void _internal_move_to_destination(const feedRate_t &fr_mm_s/*=0.0f*/ feedrate_percentage = 100; #if EXTRUDERS - const float old_fac = planner.e_factor[active_extruder]; - planner.e_factor[active_extruder] = 1.0f; + const float old_fac = planner.e_factor[active_extruder]; + planner.e_factor[active_extruder] = 1.0f; #endif #if IS_KINEMATIC From e275cd379815df003ce21df1022a81f5bb0e8f25 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 17 May 2020 20:46:00 -0500 Subject: [PATCH 0495/1454] =?UTF-8?q?Update=20some=20=C2=A9?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/spindle_laser_types.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index 9e3f2bae48..7fa93420d1 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h index 34c265c47b..5e8f89d56d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h index 9091c99dfc..e6cf4e528c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm From 6e01079b481665be8e7ffed903dcbefe7f422ea6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 17 May 2020 20:57:07 -0500 Subject: [PATCH 0496/1454] G29 patch followup --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index c48c693b78..9c5907a5cc 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -419,7 +419,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (TERN_(PROBE_MANUALLY, !no_action) + if (TERN1(PROBE_MANUALLY, !no_action) && (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start) ) { // Reset grid to 0.0 or "not probed". (Also disables ABL) From 213d4b890ea4997db63b0946cde766581d7f96e5 Mon Sep 17 00:00:00 2001 From: Italo Soares Date: Mon, 18 May 2020 02:50:35 -0300 Subject: [PATCH 0497/1454] Hotend Idle Timeout (#16362) --- Marlin/Configuration_adv.h | 14 ++++- Marlin/src/MarlinCore.cpp | 6 ++ Marlin/src/feature/hotend_idle.cpp | 89 +++++++++++++++++++++++++++ Marlin/src/feature/hotend_idle.h | 37 +++++++++++ Marlin/src/inc/Conditionals_LCD.h | 1 + Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/module/temperature.h | 8 +++ buildroot/share/tests/esp32-tests | 3 +- 8 files changed, 157 insertions(+), 2 deletions(-) create mode 100644 Marlin/src/feature/hotend_idle.cpp create mode 100644 Marlin/src/feature/hotend_idle.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 20c110ff7b..9d1118838a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -330,6 +330,18 @@ #define EXTRUDER_RUNOUT_EXTRUDE 5 // (mm) #endif +/** + * Hotend Idle Timeout + * Prevent filament in the nozzle from charring and causing a critical jam. + */ +//#define HOTEND_IDLE_TIMEOUT +#if ENABLED(HOTEND_IDLE_TIMEOUT) + #define HOTEND_IDLE_DURATION_SEC 5 // (minutes) Time without extruder movement to trigger protection + #define HOTEND_IDLE_MIN_TRIGGER 180 // (°C) Minimum temperature to enable hotend protection + #define HOTEND_IDLE_NOZZLE_TARGET 0 // (°C) Safe temperature for the nozzle after timeout + #define HOTEND_IDLE_BED_TARGET 0 // (°C) Safe temperature for the bed after timeout +#endif + // @section temperature // Calibration for AD595 / AD8495 sensor to adjust temperature measurements. @@ -3308,7 +3320,7 @@ */ //#define MMU_EXTRUDER_SENSOR - #if ENABLED(MMU_EXTRUDER_SENSOR) + #if ENABLED(MMU_EXTRUDER_SENSOR) #define MMU_LOADING_ATTEMPTS_NR 5 //max. number of attempts to load filament if first load fail #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 2434df0ad4..3b07676840 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -159,6 +159,10 @@ #include "feature/runout.h" #endif +#if ENABLED(HOTEND_IDLE_TIMEOUT) + #include "feature/hotend_idle.h" +#endif + #if ENABLED(TEMP_STAT_LEDS) #include "feature/leds/tempstat.h" #endif @@ -527,6 +531,8 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { TERN_(AUTO_POWER_CONTROL, powerManager.check()); + TERN_(HOTEND_IDLE_TIMEOUT, hotend_idle.check()); + #if ENABLED(EXTRUDER_RUNOUT_PREVENT) if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP && ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS)) diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp new file mode 100644 index 0000000000..6b5d1b276d --- /dev/null +++ b/Marlin/src/feature/hotend_idle.cpp @@ -0,0 +1,89 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Hotend Idle Timeout + * Prevent filament in the nozzle from charring and causing a critical jam. + */ + +#include "../inc/MarlinConfig.h" + +#if ENABLED(HOTEND_IDLE_TIMEOUT) + +#include "hotend_idle.h" +#include "../gcode/gcode.h" + +#include "../module/temperature.h" +#include "../module/motion.h" +#include "../lcd/ultralcd.h" + +extern HotendIdleProtection hotend_idle; + +millis_t HotendIdleProtection::next_protect_ms = 0; + +void HotendIdleProtection::check_hotends(const millis_t &ms) { + bool do_prot = false; + HOTEND_LOOP() { + if (thermalManager.degHotendNear(e, HOTEND_IDLE_MIN_TRIGGER)) { + do_prot = true; break; + } + } + if (bool(next_protect_ms) != do_prot) + next_protect_ms = do_prot ? ms + hp_interval : 0; +} + +void HotendIdleProtection::check_e_motion(const millis_t &ms) { + static float old_e_position = 0; + if (old_e_position != current_position.e) { + old_e_position = current_position.e; // Track filament motion + if (next_protect_ms) // If some heater is on then... + next_protect_ms = ms + hp_interval; // ...delay the timeout till later + } +} + +void HotendIdleProtection::check() { + const millis_t ms = millis(); // Shared millis + + check_hotends(ms); // Any hotends need protection? + check_e_motion(ms); // Motion will protect them + + // Hot and not moving for too long... + if (next_protect_ms && ELAPSED(ms, next_protect_ms)) + timed_out(); +} + +// Lower (but don't raise) hotend / bed temperatures +void HotendIdleProtection::timed_out() { + next_protect_ms = 0; + SERIAL_ECHOLNPGM("Hotend Idle Timeout"); + LCD_MESSAGEPGM(MSG_HOTEND_IDLE_TIMEOUT); + HOTEND_LOOP() { + if ((HOTEND_IDLE_NOZZLE_TARGET) < thermalManager.degTargetHotend(e)) + thermalManager.setTargetHotend(HOTEND_IDLE_NOZZLE_TARGET, e); + } + #if HAS_HEATED_BED + if ((HOTEND_IDLE_BED_TARGET) < thermalManager.degTargetBed()) + thermalManager.setTargetBed(HOTEND_IDLE_BED_TARGET); + #endif +} + +#endif // HOTEND_IDLE_TIMEOUT diff --git a/Marlin/src/feature/hotend_idle.h b/Marlin/src/feature/hotend_idle.h new file mode 100644 index 0000000000..298439da29 --- /dev/null +++ b/Marlin/src/feature/hotend_idle.h @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../core/millis_t.h" + +class HotendIdleProtection { +public: + static void check(); +private: + static constexpr millis_t hp_interval = SEC_TO_MS(HOTEND_IDLE_DURATION_SEC); + static millis_t next_protect_ms; + static void check_hotends(const millis_t &ms); + static void check_e_motion(const millis_t &ms); + static void timed_out(); +}; + +extern HotendIdleProtection hotend_idle; diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 47a94d0074..11cf582637 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -414,6 +414,7 @@ #undef MIXING_EXTRUDER #undef MK2_MULTIPLEXER #undef PRUSA_MMU2 + #undef HOTEND_IDLE_TIMEOUT #endif #if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 3ee5bea6e4..b8013bf16c 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -488,6 +488,7 @@ namespace Language_en { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocol"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: OFF"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: ON"); + PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case Light"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 155644e7f8..b2c5497b00 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -612,6 +612,10 @@ class Temperature { return degTargetHotend(e) > TEMP_HYSTERESIS && ABS(degHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS; } + FORCE_INLINE static bool degHotendNear(const uint8_t e, const float &temp) { + return ABS(degHotend(e) - temp) < (TEMP_HYSTERESIS); + } + #endif // HOTENDS #if HAS_HEATED_BED @@ -650,6 +654,10 @@ class Temperature { static void wait_for_bed_heating(); + FORCE_INLINE static bool degBedNear(const float &temp) { + return ABS(degBed() - temp) < (TEMP_BED_HYSTERESIS); + } + #endif // HAS_HEATED_BED #if HAS_TEMP_PROBE diff --git a/buildroot/share/tests/esp32-tests b/buildroot/share/tests/esp32-tests index 37a67fcae6..ccc01a1c1c 100755 --- a/buildroot/share/tests/esp32-tests +++ b/buildroot/share/tests/esp32-tests @@ -31,7 +31,8 @@ opt_set X_HARDWARE_SERIAL Serial1 opt_set Y_HARDWARE_SERIAL Serial1 opt_set Z_HARDWARE_SERIAL Serial1 opt_set E0_HARDWARE_SERIAL Serial1 -exec_test $1 $2 "ESP32 with TMC Hardware Serial" +opt_enable HOTEND_IDLE_TIMEOUT +exec_test $1 $2 "ESP32, TMC HW Serial, Hotend Idle" # cleanup restore_configs From 94063e3a873d3e3644d1c363cd4d6eec82de649f Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 18 May 2020 11:51:32 -0700 Subject: [PATCH 0498/1454] Fix PID + Thermal Protection combos (#18023) --- Marlin/Configuration.h | 14 +++++++++----- Marlin/src/module/temperature.cpp | 14 +++++++------- buildroot/share/tests/mks_robin_pro-tests | 6 ++++-- buildroot/share/tests/rumba32_f446ve-tests | 6 +++++- 4 files changed, 25 insertions(+), 15 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 777f9a534b..25f359c13c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -479,16 +479,12 @@ #define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current #define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current #define PID_K1 0.95 // Smoothing factor within any PID loop + #if ENABLED(PIDTEMP) //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM) //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) - //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. - //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX - //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) // Set/get with gcode: M301 E[extruder number, 0-2] - #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature - // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it @@ -557,6 +553,14 @@ // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. #endif // PIDTEMPBED +#if EITHER(PIDTEMP, PIDTEMPBED) + //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. + //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX + //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay + #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature + // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. +#endif + // @section extruder /** diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 7518e0ef2c..f9482aedb2 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -381,15 +381,15 @@ volatile bool Temperature::raw_temps_ready = false; #define ONHEATINGSTART() printerEventLEDs.onHotendHeatingStart() #define ONHEATING(S,C,T) printerEventLEDs.onHotendHeating(S,C,T) #endif + #define WATCH_PID BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP) - #if WATCH_BED || WATCH_HOTENDS - #define HAS_TP_BED BOTH(THERMAL_PROTECTION_BED, PIDTEMPBED) - #if HAS_TP_BED && BOTH(THERMAL_PROTECTION_HOTENDS, PIDTEMP) + #if WATCH_PID + #if ALL(THERMAL_PROTECTION_HOTENDS, PIDTEMP, THERMAL_PROTECTION_BED, PIDTEMPBED) #define GTV(B,H) (isbed ? (B) : (H)) - #elif HAS_TP_BED - #define GTV(B,H) (B) - #else + #elif BOTH(THERMAL_PROTECTION_HOTENDS, PIDTEMP) #define GTV(B,H) (H) + #else + #define GTV(B,H) (B) #endif const uint16_t watch_temp_period = GTV(WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); const uint8_t watch_temp_increase = GTV(WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); @@ -528,7 +528,7 @@ volatile bool Temperature::raw_temps_ready = false; next_temp_ms = ms + 2000UL; // Make sure heating is actually working - #if WATCH_BED || WATCH_HOTENDS + #if WATCH_PID if (BOTH(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS)) { if (!heated) { // If not yet reached target... if (current_temp > next_watch_temp) { // Over the watch temp? diff --git a/buildroot/share/tests/mks_robin_pro-tests b/buildroot/share/tests/mks_robin_pro-tests index 4b437e0e03..cfd36832fd 100644 --- a/buildroot/share/tests/mks_robin_pro-tests +++ b/buildroot/share/tests/mks_robin_pro-tests @@ -10,7 +10,9 @@ use_example_configs Mks/Robin_Pro opt_set SDCARD_CONNECTION LCD opt_set X_DRIVER_TYPE TMC2209 opt_set Y_DRIVER_TYPE TMC2130 -exec_test $1 $2 "MKS Robin Pro with TMC Drivers " +opt_set TEMP_SENSOR_BED 1 +opt_disable THERMAL_PROTECTION_HOTENDS +exec_test $1 $2 "MKS Robin Pro with TMC Drivers, hotend thermal protection disabled" # cleanup -restore_configs +#restore_configs diff --git a/buildroot/share/tests/rumba32_f446ve-tests b/buildroot/share/tests/rumba32_f446ve-tests index a0286b54a9..868bbe5338 100644 --- a/buildroot/share/tests/rumba32_f446ve-tests +++ b/buildroot/share/tests/rumba32_f446ve-tests @@ -10,8 +10,12 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_RUMBA32_AUS3D opt_set SERIAL_PORT -1 +opt_disable PIDTEMP +opt_enable PIDTEMPBED +opt_set TEMP_SENSOR_BED 1 +opt_disable THERMAL_PROTECTION_BED opt_set X_DRIVER_TYPE TMC2130 -exec_test $1 $2 "rumba32_f446ve Default Config with TMC2130" +exec_test $1 $2 "rumba32_f446ve with TMC2130, PID Bed, and bed thermal protection disabled" # cleanup restore_configs From 63c43de9b425ae042add4d14041053a3c5d2f157 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 19 May 2020 00:04:18 +0000 Subject: [PATCH 0499/1454] [cron] Bump distribution date (2020-05-19) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index abe4df3286..349e20043d 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-18" + #define STRING_DISTRIBUTION_DATE "2020-05-19" #endif /** From bce952770992bb9e1dbb7f943d67d9839e32b1a0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 18 May 2020 22:52:13 -0500 Subject: [PATCH 0500/1454] Whitespace --- Marlin/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 25f359c13c..cb5ae06617 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -559,7 +559,7 @@ //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. -#endif +#endif // @section extruder From 7696dea1c6eeddb1f1dd99e8acb480c2aab8f28d Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Tue, 19 May 2020 00:29:19 -0700 Subject: [PATCH 0501/1454] Fix LPC + EXPERIMENTAL_I2CBUS build error (#18040) --- Marlin/src/HAL/LPC1768/HAL.h | 2 +- buildroot/share/tests/LPC1769-tests | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 2d385fd16c..7d2b289f35 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -49,7 +49,7 @@ extern "C" volatile uint32_t _millis; #include // i2c uses 8-bit shifted address -#define I2C_ADDRESS(A) ((A) << 1) +#define I2C_ADDRESS(A) uint8_t((A) << 1) // // Default graphical display delays diff --git a/buildroot/share/tests/LPC1769-tests b/buildroot/share/tests/LPC1769-tests index 53a7b28189..9c7a1ba10e 100755 --- a/buildroot/share/tests/LPC1769-tests +++ b/buildroot/share/tests/LPC1769-tests @@ -49,7 +49,8 @@ opt_set Y_DRIVER_TYPE TMC2130 opt_set Z_DRIVER_TYPE TMC2130 opt_enable AUTO_BED_LEVELING_BILINEAR EEPROM_SETTINGS EEPROM_CHITCHAT \ TMC_USE_SW_SPI MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z HYBRID_THRESHOLD \ - SENSORLESS_PROBING Z_SAFE_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY TMC_DEBUG + SENSORLESS_PROBING Z_SAFE_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY TMC_DEBUG \ + EXPERIMENTAL_I2CBUS opt_disable PSU_CONTROL exec_test $1 $2 "Cohesion3D Remix DELTA + ABL Bilinear + EEPROM + SENSORLESS_PROBING" From 1e32df4c7533c507c8271c570ac8e90f47b8f644 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 19 May 2020 00:34:15 -0700 Subject: [PATCH 0502/1454] Fix Hotend Idle Timeout comment (#18032) Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 2 +- Marlin/src/feature/hotend_idle.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 9d1118838a..76cf40e362 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -336,7 +336,7 @@ */ //#define HOTEND_IDLE_TIMEOUT #if ENABLED(HOTEND_IDLE_TIMEOUT) - #define HOTEND_IDLE_DURATION_SEC 5 // (minutes) Time without extruder movement to trigger protection + #define HOTEND_IDLE_TIMEOUT_SEC (5*60) // (seconds) Time without extruder movement to trigger protection #define HOTEND_IDLE_MIN_TRIGGER 180 // (°C) Minimum temperature to enable hotend protection #define HOTEND_IDLE_NOZZLE_TARGET 0 // (°C) Safe temperature for the nozzle after timeout #define HOTEND_IDLE_BED_TARGET 0 // (°C) Safe temperature for the bed after timeout diff --git a/Marlin/src/feature/hotend_idle.h b/Marlin/src/feature/hotend_idle.h index 298439da29..73de51c2dd 100644 --- a/Marlin/src/feature/hotend_idle.h +++ b/Marlin/src/feature/hotend_idle.h @@ -27,7 +27,7 @@ class HotendIdleProtection { public: static void check(); private: - static constexpr millis_t hp_interval = SEC_TO_MS(HOTEND_IDLE_DURATION_SEC); + static constexpr millis_t hp_interval = SEC_TO_MS(HOTEND_IDLE_TIMEOUT_SEC); static millis_t next_protect_ms; static void check_hotends(const millis_t &ms); static void check_e_motion(const millis_t &ms); From 7be748b9b767c5095dc90b9527bb4329da2e909a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 20 May 2020 00:04:09 +0000 Subject: [PATCH 0503/1454] [cron] Bump distribution date (2020-05-20) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 349e20043d..c7665bf52f 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-19" + #define STRING_DISTRIBUTION_DATE "2020-05-20" #endif /** From 0b0ba7dcf612a5ae0f59d3e3697e2baff8ce4464 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Wed, 20 May 2020 22:28:02 +0200 Subject: [PATCH 0504/1454] Fix LCD throttle issue (#18055) Fixes #18044 --- Marlin/src/lcd/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 76aa773cd3..12c005a918 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -881,7 +881,7 @@ void MarlinUI::update() { // Instead of tracking changes just redraw the Status Screen once per second. if (on_status_screen() && !lcd_status_update_delay--) { lcd_status_update_delay = TERN(HAS_GRAPHICAL_LCD, 12, 9); - max_display_update_time--; + if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number refresh(LCDVIEW_REDRAW_NOW); } From 7b2a056656938b19409eab44a3e7874667cdcf3b Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Wed, 20 May 2020 22:31:08 +0200 Subject: [PATCH 0505/1454] Update SAMD-RAMPS runout pin (#18048) --- Marlin/src/pins/samd/pins_RAMPS_144.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index c9cc8c3c67..54363713e7 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -130,7 +130,7 @@ #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 71 + #define FIL_RUNOUT_PIN 70 #endif #ifndef PS_ON_PIN From 60bed3434bb7aa51b02978e93dae5985ff24fe3a Mon Sep 17 00:00:00 2001 From: Mobilinkd LLC Date: Wed, 20 May 2020 15:38:29 -0500 Subject: [PATCH 0506/1454] Ignore spurious MAX31855K / 6675 thermocouple errors (#18039) --- Marlin/Configuration_adv.h | 13 +++++++ Marlin/src/module/temperature.cpp | 60 +++++++++++++++++++------------ 2 files changed, 50 insertions(+), 23 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 76cf40e362..db89a1d5e9 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -39,6 +39,19 @@ //=============================Thermal Settings ============================ //=========================================================================== +/** + * Thermocouple sensors are quite sensitive to noise. Any noise induced in + * the sensor wires, such as by stepper motor wires run in parallel to them, + * may result in the thermocouple sensor reporting spurious errors. This + * value is the number of errors which can occur in a row before the error + * is reported. This allows us to ignore intermittent error conditions while + * still detecting an actual failure, which should result in a continuous + * stream of errors from the sensor. + * + * Set this value to 0 to fail on the first error to occur. + */ +#define THERMOCOUPLE_MAX_ERRORS 15 + // // Custom Thermistor 1000 parameters // diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f9482aedb2..0b073bc16c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2060,6 +2060,10 @@ void Temperature::disable_all_heaters() { #if HAS_MAX6675 + #ifndef THERMOCOUPLE_MAX_ERRORS + #define THERMOCOUPLE_MAX_ERRORS 15 + #endif + int Temperature::read_max6675( #if COUNT_6675 > 1 const uint8_t hindex @@ -2071,6 +2075,8 @@ void Temperature::disable_all_heaters() { // Needed to return the correct temp when this is called too soon static uint16_t max6675_temp_previous[COUNT_6675] = { 0 }; #endif + + static uint8_t max6675_errors[COUNT_6675] = { 0 }; #define MAX6675_HEAT_INTERVAL 250UL @@ -2144,33 +2150,41 @@ void Temperature::disable_all_heaters() { WRITE_MAX6675(HIGH); // disable TT_MAX6675 if (max6675_temp & MAX6675_ERROR_MASK) { - SERIAL_ERROR_START(); - SERIAL_ECHOPGM("Temp measurement error! "); - #if MAX6675_ERROR_MASK == 7 - SERIAL_ECHOPGM("MAX31855 "); - if (max6675_temp & 1) - SERIAL_ECHOLNPGM("Open Circuit"); - else if (max6675_temp & 2) - SERIAL_ECHOLNPGM("Short to GND"); - else if (max6675_temp & 4) - SERIAL_ECHOLNPGM("Short to VCC"); - #else - SERIAL_ECHOLNPGM("MAX6675"); - #endif - - // Thermocouple open - max6675_temp = 4 * ( - #if COUNT_6675 > 1 - hindex ? HEATER_1_MAX6675_TMAX : HEATER_0_MAX6675_TMAX - #elif ENABLED(HEATER_1_USES_MAX6675) - HEATER_1_MAX6675_TMAX + max6675_errors[hindex] += 1; + if (max6675_errors[hindex] > THERMOCOUPLE_MAX_ERRORS) { + SERIAL_ERROR_START(); + SERIAL_ECHOPGM("Temp measurement error! "); + #if MAX6675_ERROR_MASK == 7 + SERIAL_ECHOPGM("MAX31855 "); + if (max6675_temp & 1) + SERIAL_ECHOLNPGM("Open Circuit"); + else if (max6675_temp & 2) + SERIAL_ECHOLNPGM("Short to GND"); + else if (max6675_temp & 4) + SERIAL_ECHOLNPGM("Short to VCC"); #else - HEATER_0_MAX6675_TMAX + SERIAL_ECHOLNPGM("MAX6675"); #endif - ); + + // Thermocouple open + max6675_temp = 4 * ( + #if COUNT_6675 > 1 + hindex ? HEATER_1_MAX6675_TMAX : HEATER_0_MAX6675_TMAX + #elif ENABLED(HEATER_1_USES_MAX6675) + HEATER_1_MAX6675_TMAX + #else + HEATER_0_MAX6675_TMAX + #endif + ); + } + else { + max6675_temp >>= MAX6675_DISCARD_BITS; + } } - else + else { max6675_temp >>= MAX6675_DISCARD_BITS; + max6675_errors[hindex] = 0; + } #if ENABLED(MAX6675_IS_MAX31855) if (max6675_temp & 0x00002000) max6675_temp |= 0xFFFFC000; // Support negative temperature From 9bf768a3fbefdc270efa237a10a9031c975878d3 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Wed, 20 May 2020 22:39:08 +0200 Subject: [PATCH 0507/1454] Update Italian language (#18049) --- Marlin/src/lcd/language/language_it.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index f7dce0709d..aa853e56f4 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -342,6 +342,7 @@ namespace Language_it { PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Stampa"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetta"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignora"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Annulla"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fatto"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Indietro"); @@ -485,8 +486,12 @@ namespace Language_it { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocollo"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Controllo fuga: OFF"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Controllo fuga: ON"); + PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Timeout inatt.ugello"); + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luci Case"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci"); + PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("STAMPANTE ERRATA"); + #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Contat. stampa"); PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); @@ -570,7 +575,8 @@ namespace Language_it { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Stampante errata"); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Indice pag. errato"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Vel. pag. errata"); // // Le schermate di Cambio Filamento possono visualizzare fino a 3 linee su un display a 4 righe From 4e512405633911f8809f774c175c270d288a8586 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 20 May 2020 13:42:45 -0700 Subject: [PATCH 0508/1454] BTT GTR has I2C EEPROM (#18029) --- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 16 ++++------------ 1 file changed, 4 insertions(+), 12 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index ce3a282b5e..47fcb97be5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -31,18 +31,10 @@ #define BOARD_INFO_NAME "BIGTREE GTR 1.0" -// Use one of these or SDCard-based Emulation will be used -#if NO_EEPROM_SELECTED - //#define I2C_EEPROM - //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation - //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation -#endif - -#if ENABLED(FLASH_EEPROM_EMULATION) - // Decrease delays and flash wear by spreading writes across the - // 128 kB sector allocated for EEPROM emulation. - #define FLASH_EEPROM_LEVELING -#endif +// Onboard I2C EEPROM +#define I2C_EEPROM +#undef E2END +#define E2END 0x1FFF // EEPROM end address 24C64 (64Kb = 8KB) #define TP // Enable to define servo and probe pins From 8cfcabe14602b459923c02e43a730fec4ac70e42 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 21 May 2020 00:04:28 +0000 Subject: [PATCH 0509/1454] [cron] Bump distribution date (2020-05-21) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c7665bf52f..bee3a5ced8 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-20" + #define STRING_DISTRIBUTION_DATE "2020-05-21" #endif /** From f7346b6ee12b2153f84fd34faf6b954a5d76ab91 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 22 May 2020 00:04:21 +0000 Subject: [PATCH 0510/1454] [cron] Bump distribution date (2020-05-22) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bee3a5ced8..e0f8987373 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-21" + #define STRING_DISTRIBUTION_DATE "2020-05-22" #endif /** From 31eb487da5778f653c771331bcef6b57e3511404 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 22 May 2020 02:02:03 -0500 Subject: [PATCH 0511/1454] whitespace --- Marlin/Configuration_adv.h | 2 +- Marlin/src/feature/direct_stepping.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h | 3 +-- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 4 ++-- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 4 ++-- 6 files changed, 8 insertions(+), 9 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index db89a1d5e9..22755f8122 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -47,7 +47,7 @@ * is reported. This allows us to ignore intermittent error conditions while * still detecting an actual failure, which should result in a continuous * stream of errors from the sensor. - * + * * Set this value to 0 to fail on the first error to occur. */ #define THERMOCOUPLE_MAX_ERRORS 15 diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index 7bed075b87..76dfac7de5 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -61,7 +61,7 @@ namespace DirectStepping { template uint8_t SerialPageManager::pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE]; - + template uint8_t SerialPageManager::checksum; diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 0b073bc16c..6121a5a0ac 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2075,7 +2075,7 @@ void Temperature::disable_all_heaters() { // Needed to return the correct temp when this is called too soon static uint16_t max6675_temp_previous[COUNT_6675] = { 0 }; #endif - + static uint8_t max6675_errors[COUNT_6675] = { 0 }; #define MAX6675_HEAT_INTERVAL 250UL diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index dd4cb4ea08..601edc83d0 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -47,7 +47,6 @@ #define PS_ON_PIN 40 // Used by CR2020 Industrial series #endif - #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) #define CASE_LIGHT_PIN 65 #endif @@ -65,5 +64,5 @@ #define SUICIDE_PIN 12 // Used by CR2020 Industrial series #ifndef SUICIDE_PIN_INVERTING - #define SUICIDE_PIN_INVERTING true + #define SUICIDE_PIN_INVERTING true #endif diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index cfb9acb054..a512aa8353 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -59,7 +59,7 @@ #define RAMPS_D10_PIN TG_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h -#if HAS_MULTI_HOTEND // EEF and EEB +#if HAS_MULTI_HOTEND // EEF and EEB #define RAMPS_D9_PIN TG_HEATER_1_PIN #if !TEMP_SENSOR_BED // EEF @@ -79,7 +79,7 @@ #define RAMPS_D8_PIN TG_FAN0_PIN #endif -#if HAS_MULTI_HOTEND || TEMP_SENSOR_BED // EEF, EEB, EFB +#if HAS_MULTI_HOTEND || TEMP_SENSOR_BED // EEF, EEB, EFB #define FAN1_PIN TG_FAN1_PIN #endif #define FAN2_PIN TG_FAN2_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index 3df81a7842..ba1ea08796 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -352,8 +352,8 @@ *  ̄ ̄ * W1 */ -#define ESP_WIFI_MODULE_COM 6 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this -#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_COM 6 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 #define ESP_WIFI_MODULE_RESET_PIN PG0 #define ESP_WIFI_MODULE_ENABLE_PIN PG1 #define ESP_WIFI_MODULE_GPIO0_PIN PF14 From 461647fcee5f9d519e0e54f809dbfb38bf573e59 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 22 May 2020 02:15:40 -0500 Subject: [PATCH 0512/1454] Use MARLIN_EEPROM_SIZE with E2END as fallback (#18059) --- Marlin/src/HAL/AVR/eeprom.cpp | 5 +- Marlin/src/HAL/DUE/eeprom_flash.cpp | 9 ++- Marlin/src/HAL/DUE/eeprom_wired.cpp | 5 +- Marlin/src/HAL/ESP32/eeprom.cpp | 17 ++--- Marlin/src/HAL/LINUX/eeprom.cpp | 15 ++-- Marlin/src/HAL/LPC1768/eeprom_flash.cpp | 27 +++---- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 5 +- Marlin/src/HAL/LPC1768/eeprom_wired.cpp | 12 ++-- Marlin/src/HAL/SAMD51/eeprom_wired.cpp | 12 ++-- Marlin/src/HAL/STM32/eeprom_flash.cpp | 39 +++++----- Marlin/src/HAL/STM32/eeprom_sdcard.cpp | 71 ++++++++----------- Marlin/src/HAL/STM32/eeprom_sram.cpp | 6 +- Marlin/src/HAL/STM32/eeprom_wired.cpp | 12 ++-- Marlin/src/HAL/STM32F1/eeprom_flash.cpp | 18 ++--- Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp | 22 +++--- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 8 ++- Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp | 8 ++- Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp | 12 ++-- Marlin/src/HAL/TEENSY31_32/eeprom.cpp | 8 ++- Marlin/src/HAL/TEENSY35_36/eeprom.cpp | 6 +- Marlin/src/module/configuration_store.cpp | 2 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 4 +- Marlin/src/pins/sam/pins_RADDS.h | 2 +- Marlin/src/pins/sam/pins_RAMPS_FD_V2.h | 2 +- Marlin/src/pins/sam/pins_RAMPS_SMART.h | 2 +- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 2 +- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 2 +- Marlin/src/pins/samd/pins_RAMPS_144.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 6 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 3 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 2 +- Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h | 3 +- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 3 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 2 +- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 6 +- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 7 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 2 +- Marlin/src/pins/stm32f4/pins_ARMED.h | 4 +- .../src/pins/stm32f4/pins_BLACK_STM32F407VE.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 3 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 3 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 3 +- .../src/pins/stm32f4/pins_GENERIC_STM32F4.h | 4 +- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 5 +- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 3 +- Marlin/src/pins/stm32f7/pins_THE_BORG.h | 4 +- 49 files changed, 205 insertions(+), 201 deletions(-) diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index 0519e5732e..7f43842155 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -32,7 +32,10 @@ #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index c07d05adfc..cb27e23c58 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -26,10 +26,6 @@ #if ENABLED(FLASH_EEPROM_EMULATION) -#ifndef E2END - #define E2END 0xFFF // Default to Flash emulated EEPROM size (eeprom_emul.cpp) -#endif - /* EEPROM emulation over flash with reduced wear * * We will use 2 contiguous groups of pages as main and alternate. @@ -973,7 +969,10 @@ static void ee_Init() { #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { ee_Init(); return true; } bool PersistentStore::access_finish() { ee_Flush(); return true; } diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index a9b2cc92d2..e26d19f366 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -34,7 +34,10 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/ESP32/eeprom.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp index 35cebb592f..27974fe55e 100644 --- a/Marlin/src/HAL/ESP32/eeprom.cpp +++ b/Marlin/src/HAL/ESP32/eeprom.cpp @@ -28,16 +28,13 @@ #include "../shared/eeprom_api.h" #include -#define EEPROM_SIZE 4096 +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_start() { - return EEPROM.begin(EEPROM_SIZE); -} - -bool PersistentStore::access_finish() { - EEPROM.end(); - return true; -} +bool PersistentStore::access_start() { return EEPROM.begin(MARLIN_EEPROM_SIZE); } +bool PersistentStore::access_finish() { EEPROM.end(); return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { for (size_t i = 0; i < size; i++) { @@ -56,7 +53,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { return EEPROM_SIZE; } - #endif // EEPROM_SETTINGS #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/LINUX/eeprom.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp index 7a9a1db381..50f33eae21 100644 --- a/Marlin/src/HAL/LINUX/eeprom.cpp +++ b/Marlin/src/HAL/LINUX/eeprom.cpp @@ -28,10 +28,15 @@ #include "../shared/eeprom_api.h" #include -#define LINUX_EEPROM_SIZE (E2END + 1) -uint8_t buffer[LINUX_EEPROM_SIZE]; +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB of Emulated EEPROM +#endif + +uint8_t buffer[MARLIN_EEPROM_SIZE]; char filename[] = "eeprom.dat"; +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + bool PersistentStore::access_start() { const char eeprom_erase_value = 0xFF; FILE * eeprom_file = fopen(filename, "rb"); @@ -40,8 +45,8 @@ bool PersistentStore::access_start() { fseek(eeprom_file, 0L, SEEK_END); std::size_t file_size = ftell(eeprom_file); - if (file_size < LINUX_EEPROM_SIZE) { - memset(buffer + file_size, eeprom_erase_value, LINUX_EEPROM_SIZE - file_size); + if (file_size < MARLIN_EEPROM_SIZE) { + memset(buffer + file_size, eeprom_erase_value, MARLIN_EEPROM_SIZE - file_size); } else { fseek(eeprom_file, 0L, SEEK_SET); @@ -95,7 +100,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin return bytes_read != size; // return true for any error } -size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM - #endif // EEPROM_SETTINGS #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp index 3bcda68adb..759b01b365 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp @@ -46,19 +46,22 @@ extern "C" { #include } -#define SECTOR_START(sector) ((sector < 16) ? (sector * 0x1000) : ((sector - 14) * 0x8000)) -#define EEPROM_SECTOR 29 -#define EEPROM_SIZE (4096) -#define SECTOR_SIZE (32768) -#define EEPROM_SLOTS (SECTOR_SIZE/EEPROM_SIZE) -#define EEPROM_ERASE (0xFF) -#define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * EEPROM_SIZE) +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif -static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0}; +#define SECTOR_START(sector) ((sector < 16) ? (sector << 12) : ((sector - 14) << 15)) +#define EEPROM_SECTOR 29 +#define SECTOR_SIZE 32768 +#define EEPROM_SLOTS ((SECTOR_SIZE)/(MARLIN_EEPROM_SIZE)) +#define EEPROM_ERASE 0xFF +#define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * (MARLIN_EEPROM_SIZE)) + +static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; static int current_slot = 0; -size_t PersistentStore::capacity() { return EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { uint32_t first_nblank_loc, first_nblank_val; @@ -71,15 +74,15 @@ bool PersistentStore::access_start() { if (status == CMD_SUCCESS) { // sector is blank so nothing stored yet - for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE; + for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE; current_slot = EEPROM_SLOTS; } else { // current slot is the first non blank one - current_slot = first_nblank_loc / EEPROM_SIZE; + current_slot = first_nblank_loc / (MARLIN_EEPROM_SIZE); uint8_t *eeprom_data = SLOT_ADDRESS(EEPROM_SECTOR, current_slot); // load current settings - for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; + for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; } eeprom_dirty = false; diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index aac41ab307..92a9d6f0c0 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -38,7 +38,10 @@ FATFS fat_fs; FIL eeprom_file; bool eeprom_file_open = false; -size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(0x1000) // 4KiB of Emulated EEPROM +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { const char eeprom_erase_value = 0xFF; diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index 255ff6faad..6daedc50e0 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -33,18 +33,14 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -#ifndef EEPROM_SIZE - #define EEPROM_SIZE 0x8000 // 32kB‬ +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x8000 // 32KB‬ #endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -size_t PersistentStore::capacity() { return EEPROM_SIZE; } +bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } -bool PersistentStore::access_start() { - eeprom_init(); - return true; -} - bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t v = *value; diff --git a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp index e5c14e9cbf..22210dc49e 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp @@ -32,13 +32,13 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_finish() { return true; } +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_start() { - eeprom_init(); - return true; -} +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 309c5eea9f..57713593c8 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -32,7 +32,7 @@ #include "Servo.h" #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() -#else +#else #define PAUSE_SERVO_OUTPUT() #define RESUME_SERVO_OUTPUT() #endif @@ -59,8 +59,8 @@ #define DEBUG_OUT ENABLED(EEPROM_CHITCHAT) #include "src/core/debug_out.h" - #ifndef EEPROM_SIZE - #define EEPROM_SIZE 0x1000 // 4kB + #ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif #ifndef FLASH_SECTOR @@ -70,11 +70,11 @@ #define FLASH_UNIT_SIZE 0x20000 // 128kB #endif - #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - FLASH_SECTOR) * FLASH_UNIT_SIZE) + 1) + #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1) #define FLASH_ADDRESS_END (FLASH_ADDRESS_START + FLASH_UNIT_SIZE - 1) - #define EEPROM_SLOTS (FLASH_UNIT_SIZE/EEPROM_SIZE) - #define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * EEPROM_SIZE)) + #define EEPROM_SLOTS ((FLASH_UNIT_SIZE) / (MARLIN_EEPROM_SIZE)) + #define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * (MARLIN_EEPROM_SIZE))) #define UNLOCK_FLASH() if (!flash_unlocked) { \ HAL_FLASH_Unlock(); \ @@ -87,12 +87,12 @@ #define EMPTY_UINT32 ((uint32_t)-1) #define EMPTY_UINT8 ((uint8_t)-1) - static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0}; + static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static int current_slot = -1; - static_assert(0 == EEPROM_SIZE % 4, "EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe - static_assert(0 == FLASH_UNIT_SIZE % EEPROM_SIZE, "EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE"); - static_assert(FLASH_UNIT_SIZE >= EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your EEPROM_SIZE"); + static_assert(0 == MARLIN_EEPROM_SIZE % 4, "MARLIN_EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe + static_assert(0 == FLASH_UNIT_SIZE % MARLIN_EEPROM_SIZE, "MARLIN_EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE"); + static_assert(FLASH_UNIT_SIZE >= MARLIN_EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your MARLIN_EEPROM_SIZE"); static_assert(IS_FLASH_SECTOR(FLASH_SECTOR), "FLASH_SECTOR is invalid"); static_assert(IS_POWER_OF_2(FLASH_UNIT_SIZE), "FLASH_UNIT_SIZE should be a power of 2, please check your chip's spec sheet"); @@ -100,6 +100,11 @@ static bool eeprom_data_written = false; +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + bool PersistentStore::access_start() { #if ENABLED(FLASH_EEPROM_LEVELING) @@ -113,20 +118,20 @@ bool PersistentStore::access_start() { while (address <= FLASH_ADDRESS_END) { uint32_t address_value = (*(__IO uint32_t*)address); if (address_value != EMPTY_UINT32) { - current_slot = (address - FLASH_ADDRESS_START) / EEPROM_SIZE; + current_slot = (address - (FLASH_ADDRESS_START)) / (MARLIN_EEPROM_SIZE); break; } address += sizeof(uint32_t); } if (current_slot == -1) { // We didn't find anything, so we'll just intialize to empty - for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8; + for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8; current_slot = EEPROM_SLOTS; } else { // load current settings uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot); - for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; + for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; DEBUG_ECHOLNPAIR("EEPROM loaded from slot ", current_slot, "."); } eeprom_data_written = false; @@ -146,7 +151,7 @@ bool PersistentStore::access_finish() { // MCU may come up with flash error bits which prevent some flash operations. // Clear flags prior to flash operations to prevent errors. __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - #endif + #endif #if ENABLED(FLASH_EEPROM_LEVELING) @@ -185,7 +190,7 @@ bool PersistentStore::access_finish() { uint32_t offset = 0; uint32_t address = SLOT_ADDRESS(current_slot); - uint32_t address_end = address + EEPROM_SIZE; + uint32_t address_end = address + MARLIN_EEPROM_SIZE; uint32_t data = 0; bool success = true; @@ -267,9 +272,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t return false; } -size_t PersistentStore::capacity() { - return TERN(FLASH_EEPROM_LEVELING, EEPROM_SIZE, E2END + 1); -} - #endif // FLASH_EEPROM_EMULATION #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp index 2b89c21b89..2fcf5ec3d9 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -31,53 +31,44 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) #include "../shared/eeprom_api.h" +#include "../../sd/cardreader.h" -#ifndef E2END - #define E2END 0xFFF // 4KB +#define EEPROM_FILENAME "eeprom.dat" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -#define HAL_EEPROM_SIZE int(E2END + 1) +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } #define _ALIGN(x) __attribute__ ((aligned(x))) -static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE]; +static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; -#if ENABLED(SDSUPPORT) +bool PersistentStore::access_start() { + if (!card.isMounted()) return false; - #include "../../sd/cardreader.h" - - #define EEPROM_FILENAME "eeprom.dat" - - bool PersistentStore::access_start() { - if (!card.isMounted()) return false; - - SdFile file, root = card.getroot(); - if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) - return true; - - int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE); - if (bytes_read < 0) return false; - for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++) - HAL_eeprom_data[bytes_read] = 0xFF; - file.close(); + SdFile file, root = card.getroot(); + if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) return true; + + int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE); + if (bytes_read < 0) return false; + for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++) + HAL_eeprom_data[bytes_read] = 0xFF; + file.close(); + return true; +} + +bool PersistentStore::access_finish() { + if (!card.isMounted()) return false; + + SdFile file, root = card.getroot(); + int bytes_written = 0; + if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { + bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE); + file.close(); } - - bool PersistentStore::access_finish() { - if (!card.isMounted()) return false; - - SdFile file, root = card.getroot(); - int bytes_written = 0; - if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { - bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE); - file.close(); - } - return (bytes_written == HAL_EEPROM_SIZE); - } - -#else // !SDSUPPORT - - #error "Please define an EEPROM, a SDCARD or disable EEPROM_SETTINGS." - -#endif // !SDSUPPORT + return (bytes_written == MARLIN_EEPROM_SIZE); +} bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { for (size_t i = 0; i < size; i++) @@ -97,7 +88,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin return false; } -size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } - #endif // SDCARD_EEPROM_EMULATION #endif // STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index 0993dee33d..6406314287 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -29,7 +29,11 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return 4096; } // 4K of SRAM +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index 084b9e6eab..7fe1116d61 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -34,13 +34,13 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_finish() { return true; } +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_start() { - eeprom_init(); - return true; -} +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp index 9c81730465..57a2bc5bed 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp @@ -39,18 +39,20 @@ #include // Store settings in the last two pages -#define EEPROM_SIZE (EEPROM_PAGE_SIZE * 2) -#define ACCESS_FINISHED(TF) do{ FLASH_Lock(); eeprom_dirty = false; return TF; }while(0) +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE ((EEPROM_PAGE_SIZE) * 2) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0}; +static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; bool PersistentStore::access_start() { const uint32_t* source = reinterpret_cast(EEPROM_PAGE0_BASE); uint32_t* destination = reinterpret_cast(ram_eeprom); - static_assert(0 == EEPROM_SIZE % 4, "EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe - constexpr size_t eeprom_size_u32 = EEPROM_SIZE / 4; + static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe + constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4; for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source) *destination = *source; @@ -72,13 +74,15 @@ bool PersistentStore::access_finish() { // page changes...either way, something to look at later. FLASH_Unlock(); + #define ACCESS_FINISHED(TF) { FLASH_Lock(); eeprom_dirty = false; return TF; } + status = FLASH_ErasePage(EEPROM_PAGE0_BASE); if (status != FLASH_COMPLETE) ACCESS_FINISHED(true); status = FLASH_ErasePage(EEPROM_PAGE1_BASE); if (status != FLASH_COMPLETE) ACCESS_FINISHED(true); const uint16_t *source = reinterpret_cast(ram_eeprom); - for (size_t i = 0; i < EEPROM_SIZE; i += 2, ++source) { + for (size_t i = 0; i < MARLIN_EEPROM_SIZE; i += 2, ++source) { if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE) ACCESS_FINISHED(false); } @@ -105,7 +109,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin return false; // return true for any error } -size_t PersistentStore::capacity() { return EEPROM_SIZE; } - #endif // FLASH_EEPROM_EMULATION #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp index bfa9b78dc9..0ca6900fa6 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp @@ -34,15 +34,15 @@ #include "../shared/eeprom_api.h" #include "../../sd/cardreader.h" -#ifndef E2END - #define E2END 0xFFF // 4KB +#define EEPROM_FILENAME "eeprom.dat" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -#define HAL_EEPROM_SIZE (E2END + 1) +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } #define _ALIGN(x) __attribute__ ((aligned(x))) // SDIO uint32_t* compat. -static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE]; - -#define EEPROM_FILENAME "eeprom.dat" +static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; bool PersistentStore::access_start() { if (!card.isMounted()) return false; @@ -51,9 +51,9 @@ bool PersistentStore::access_start() { if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) return true; // false aborts the save - int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE); + int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE); if (bytes_read < 0) return false; - for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++) + for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++) HAL_eeprom_data[bytes_read] = 0xFF; file.close(); return true; @@ -65,10 +65,10 @@ bool PersistentStore::access_finish() { SdFile file, root = card.getroot(); int bytes_written = 0; if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { - bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE); + bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE); file.close(); } - return (bytes_written == HAL_EEPROM_SIZE); + return (bytes_written == MARLIN_EEPROM_SIZE); } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { @@ -89,7 +89,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin return false; } -size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } - #endif // SDCARD_EEPROM_EMULATION #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index 8d584c67b0..5454053174 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -31,7 +31,12 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { #if ENABLED(SPI_EEPROM) @@ -45,7 +50,6 @@ bool PersistentStore::access_start() { #endif return true; } -bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp index 85503a56e5..48c0b77032 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp @@ -52,10 +52,14 @@ uint8_t ee_read_byte(uint8_t *pos) { return uint8_t(data); } -size_t PersistentStore::capacity() { return E2END + 1; } +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for Flash-based EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + bool PersistentStore::access_finish() { return true; } -bool PersistentStore::access_start() { +bool PersistentStore::access_start() { static bool ee_initialized = false; if (!ee_initialized) { HAL_FLASH_Unlock(); diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp index 08c3c30528..b362503a6b 100644 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp @@ -34,13 +34,13 @@ #include "../shared/eeprom_if.h" #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { return E2END + 1; } -bool PersistentStore::access_finish() { return true; } +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_start() { - eeprom_init(); - return true; -} +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp index 5e3c8bfcfc..d4ccfe82bb 100644 --- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp @@ -28,8 +28,14 @@ */ #include "../shared/eeprom_api.h" +#include -bool PersistentStore::access_start() { return true; } +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index 9926745511..d7cc8654ba 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -34,7 +34,11 @@ #include "../shared/eeprom_api.h" #include -size_t PersistentStore::capacity() { return E2END + 1; } +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 2ebff1f035..d86016db6d 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -389,7 +389,7 @@ typedef struct SettingsDataStruct { } SettingsData; -//static_assert(sizeof(SettingsData) <= E2END + 1, "EEPROM too small to contain SettingsData!"); +//static_assert(sizeof(SettingsData) <= MARLIN_EEPROM_SIZE, "EEPROM too small to contain SettingsData!"); MarlinSettings settings; diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 27d9bc11cc..11699375cf 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -49,7 +49,9 @@ #define BOARD_INFO_NAME "RAMPS 1.4" #endif -#define E2END 0xFFF // 4KB +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif #define IS_RAMPS_EFB diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index 3bc52e9387..0e67a77578 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -206,7 +206,7 @@ #endif #define I2C_EEPROM -#define E2END 0x1FFF // 8KB +#define MARLIN_EEPROM_SIZE 0x2000 // 8KB // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h index 6e7d055069..9dbae7773c 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h @@ -41,7 +41,7 @@ #undef INVERTED_FAN_PINS #define I2C_EEPROM -#define E2END 0xFFFF // 64K in a 24C512 +#define MARLIN_EEPROM_SIZE 0x10000 // 64K in a 24C512 #ifndef PS_ON_PIN #define PS_ON_PIN 12 diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index d82c69b254..bcd3f288ee 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -70,7 +70,7 @@ // I2C EEPROM with 4K of space #define I2C_EEPROM -#define E2END 0xFFF +#define MARLIN_EEPROM_SIZE 0x1000 #define RESET_PIN 42 // Resets the board if the jumper is attached diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 7b844b5be0..71596087de 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -186,7 +186,7 @@ // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) +#define MARLIN_EEPROM_SIZE 0x8000 // 32Kb (24lc256) #define I2C_EEPROM // EEPROM on I2C-0 //#define EEPROM_SD // EEPROM on SDCARD //#define SPI_EEPROM // EEPROM on SPI-0 diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 0d06b14936..434223a2a4 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -172,7 +172,7 @@ // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) +#define MARLIN_EEPROM_SIZE 0x8000 // 32Kb (24lc256) #define I2C_EEPROM // EEPROM on I2C-0 //#define EEPROM_SD // EEPROM on SDCARD //#define SPI_EEPROM // EEPROM on SPI-0 diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 54363713e7..566a726559 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -46,7 +46,7 @@ // //#define QSPI_EEPROM // Use AGCM4 onboard QSPI EEPROM (Uses 4K of RAM) #define I2C_EEPROM // EEPROM on I2C-0 -#define E2END 0x7FFF // 32K (24lc256) +#define MARLIN_EEPROM_SIZE 0x8000 // 32K (24lc256) // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 7dbd62accf..01dd6a7e9f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -37,8 +37,7 @@ #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #undef E2END - #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif // @@ -172,7 +171,6 @@ * EXP1 */ - #if HAS_SPI_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -276,7 +274,7 @@ // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 30963b9879..4a435d6740 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -35,8 +35,7 @@ #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #undef E2END - #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 6d42b83957..cd0ff58a29 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -37,7 +37,7 @@ #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define E2END (EEPROM_PAGE_SIZE - 1) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index b40306e22d..187aec7636 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -42,8 +42,7 @@ #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #undef E2END - #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 52444008be..e45059eab7 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -40,8 +40,7 @@ #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #undef E2END - #define E2END (EEPROM_PAGE_SIZE - 1) // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 908a100341..e7e71977c0 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -54,7 +54,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define E2END 0xFFF // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index ca1c2894cb..947bbe55cb 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -54,7 +54,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define E2END 0xFFF // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 908a100341..e7e71977c0 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -54,7 +54,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define E2END 0xFFF // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 5dbffd2897..ad140ce927 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -54,7 +54,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define E2END 0xFFF // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 340e405302..9ec0f26734 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -43,11 +43,11 @@ // Enable EEPROM Emulation for this board, so that we don't overwrite factory data //#define I2C_EEPROM // AT24C64 -//#define E2END 0x7FFFUL // 64KB +//#define MARLIN_EEPROM_SIZE 0x8000UL // 64KB //#define FLASH_EEPROM_EMULATION -//#define E2END 0xFFFUL // 4KB -//#define E2END (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL - 1UL) +//#define MARLIN_EEPROM_SIZE 0x1000UL // 4KB +//#define MARLIN_EEPROM_SIZE (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL) //#define EEPROM_CHITCHAT //#define DEBUG_EEPROM_READWRITE diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 8f5619aa69..aea7cedce7 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -152,7 +152,6 @@ #define FLASH_EEPROM_EMULATION #endif -#undef E2END #if ENABLED(SPI_EEPROM) // SPI1 EEPROM Winbond W25Q64 (8MB/64Mbits) #define SPI_CHAN_EEPROM1 1 @@ -161,12 +160,12 @@ #define EEPROM_MISO BOARD_SPI1_MISO_PIN // PA6 pin 31 #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) - #define E2END (16UL * (EEPROM_PAGE_SIZE) - 1UL) // Limit to 64KB for now... + #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define E2END (EEPROM_PAGE_SIZE - 1) + #define MARLIN_EEPROM_SIZE (EEPROM_PAGE_SIZE) #else - #define E2END (0x7FFU) // On SD, Limit to 2KB, require this amount of RAM + #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 6f3897814d..c352acc17c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -43,7 +43,7 @@ // 2K in a AT24C16N #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define E2END (EEPROM_PAGE_SIZE - 1) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB #endif // diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index ddbe09c355..d98c793639 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -39,9 +39,7 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #define I2C_EEPROM - -#undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. -#define E2END 0xFFF // 4KB +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB // // Limit Switches diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index 1a6bd80ae6..91903b5883 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -40,8 +40,8 @@ #define DEFAULT_MACHINE_NAME "STM32F407VET6" //#define I2C_EEPROM -//#define E2END 0x1FFF // 8KB #define SRAM_EEPROM_EMULATION +#define MARLIN_EEPROM_SIZE 0x2000 // 8KB // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 47fcb97be5..43c4d4279f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -33,8 +33,7 @@ // Onboard I2C EEPROM #define I2C_EEPROM -#undef E2END -#define E2END 0x1FFF // EEPROM end address 24C64 (64Kb = 8KB) +#define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24C64 ... 64Kb = 8KB) #define TP // Enable to define servo and probe pins diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 3681fde8d1..2c8f0a95bc 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -31,8 +31,7 @@ #define BOARD_WEBSITE_URL "github.com/FLYmaker/FLYF407ZG" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#undef E2END -#define E2END 0xFFF // 4KB +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 18a91d3ea0..9895213229 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -51,8 +51,7 @@ // 128 kB sector allocated for EEPROM emulation. #define FLASH_EEPROM_LEVELING #elif ENABLED(I2C_EEPROM) - #undef E2END // Defined in Arduino Core STM32 to be used with EEPROM emulation. This board uses a real EEPROM. - #define E2END 0xFFF // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // diff --git a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h index 5df7ffe466..0d9356ce52 100644 --- a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h +++ b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h @@ -36,8 +36,8 @@ //#define I2C_EEPROM -#ifndef E2END - #define E2END 0xFFF // 4KB +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // Ignore temp readings during development. diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 19853a78fe..d137332228 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -35,10 +35,7 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME //#define I2C_EEPROM -#ifdef E2END - #undef E2END -#endif -#define E2END 0xFFF // 4KB +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB // // Limit Switches diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 08f8adebc4..ccfc76146c 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -31,8 +31,7 @@ #define BOARD_INFO_NAME "STM32F4 VAkE" //#define I2C_EEPROM - -#define E2END 0xFFF // EEPROM end address (4kB) +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB // // Servos diff --git a/Marlin/src/pins/stm32f7/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h index c937c53972..ffb6638213 100644 --- a/Marlin/src/pins/stm32f7/pins_THE_BORG.h +++ b/Marlin/src/pins/stm32f7/pins_THE_BORG.h @@ -30,8 +30,8 @@ #define BOARD_INFO_NAME "The-Borge" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#ifndef E2END - #define E2END 0xFFF // EEPROM end address +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 #endif // Ignore temp readings during development. From 4f1ebb4440ec3ea7d694c229b426fd5af1a66473 Mon Sep 17 00:00:00 2001 From: Chris Pepper Date: Fri, 22 May 2020 21:37:11 +0100 Subject: [PATCH 0513/1454] Fix Due wired EEPROM init (#18074) --- Marlin/src/HAL/DUE/eeprom_wired.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index e26d19f366..6c28a6db95 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -38,7 +38,7 @@ #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." #endif size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { From 62e903c463f49528ad2d9a82eb5b0924ba45776b Mon Sep 17 00:00:00 2001 From: saxc Date: Fri, 22 May 2020 22:40:15 +0200 Subject: [PATCH 0514/1454] Update "Mac OS X" to "macOS" (#18063) --- Marlin/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index 33a787fb64..5f4fd34d57 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -14,7 +14,7 @@ # Detailed instructions for using the makefile: # # 1. Modify the line containing "ARDUINO_INSTALL_DIR" to point to the directory that -# contains the Arduino installation (for example, under Mac OS X, this +# contains the Arduino installation (for example, under macOS, this # might be /Applications/Arduino.app/Contents/Resources/Java). # # 2. Modify the line containing "UPLOAD_PORT" to refer to the filename From 8292136f776424aa6b48e7193b531713d7d7ccd0 Mon Sep 17 00:00:00 2001 From: Leo Date: Fri, 22 May 2020 22:41:32 +0200 Subject: [PATCH 0515/1454] Move DOGM progress bar up 1px (#18060) --- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index ee0b90bebf..fc67f9432a 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -104,7 +104,7 @@ #endif #define PROGRESS_BAR_X 54 -#define PROGRESS_BAR_Y (EXTRAS_BASELINE + 2) +#define PROGRESS_BAR_Y (EXTRAS_BASELINE + 1) #define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, const uint8_t ty) { From dde8fb9efbe5ea78a718a39299c12270040a9e10 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 23 May 2020 00:07:39 +0000 Subject: [PATCH 0516/1454] [cron] Bump distribution date (2020-05-23) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e0f8987373..bf35d85824 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-22" + #define STRING_DISTRIBUTION_DATE "2020-05-23" #endif /** From 7554836589d98dc8aad41651cefd12033161a725 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 24 May 2020 00:08:10 +0000 Subject: [PATCH 0517/1454] [cron] Bump distribution date (2020-05-24) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bf35d85824..bdd02bb796 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-23" + #define STRING_DISTRIBUTION_DATE "2020-05-24" #endif /** From e6e15dd764b094f51dfb9088b7fc4be64ca14963 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 25 May 2020 00:07:54 +0000 Subject: [PATCH 0518/1454] [cron] Bump distribution date (2020-05-25) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bdd02bb796..ca402935a4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-24" + #define STRING_DISTRIBUTION_DATE "2020-05-25" #endif /** From 0578bbbf5d744f025978dbc81d7941048a45698f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 23 May 2020 16:12:54 -0500 Subject: [PATCH 0519/1454] Marlin: Use strcmp_P --- Marlin/src/gcode/queue.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 4b974113fb..b98ef10992 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -523,12 +523,12 @@ void GCodeQueue::get_serial_commands() { #if DISABLED(EMERGENCY_PARSER) // Process critical commands early - if (strcmp(command, "M108") == 0) { + if (strcmp_P(command, PSTR("M108")) == 0) { wait_for_heatup = false; TERN_(HAS_LCD_MENU, wait_for_user = false); } - if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true); - if (strcmp(command, "M410") == 0) quickstop_stepper(); + if (strcmp_P(command, PSTR("M112")) == 0) kill(M112_KILL_STR, nullptr, true); + if (strcmp_P(command, PSTR("M410")) == 0) quickstop_stepper(); #endif #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0 From 929b3f6af9cc6ae551f67ad9ed844ceb80cec9d8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 23 May 2020 22:19:45 -0500 Subject: [PATCH 0520/1454] Don't re-reverse sort --- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/lcd/menu/menu_media.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 12df06c852..e1c8dd9ac6 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1000,7 +1000,7 @@ namespace ExtUI { bool FileList::seek(const uint16_t pos, const bool skip_range_check) { #if ENABLED(SDSUPPORT) if (!skip_range_check && (pos + 1) > count()) return false; - card.getfilename_sorted(SD_ORDER(pos, count())); + card.getfilename_sorted(pos); return card.filename[0] != '\0'; #else UNUSED(pos); diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 7b3d1e549c..d2514f61d2 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -126,7 +126,7 @@ void menu_media() { if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { if (_menuLineNr == _thisItemNr) { - card.getfilename_sorted(SD_ORDER(i, fileCnt)); + card.getfilename_sorted(i); if (card.flag.filenameIsDir) MENU_ITEM(sdfolder, MSG_MEDIA_MENU, card); else From 9bfdc88e522e273c9e03310b563f254c8b2f139c Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 26 May 2020 08:36:37 +1200 Subject: [PATCH 0521/1454] Provide strcmp_P where needed (#18103) --- Marlin/src/HAL/LINUX/HAL.h | 5 +++++ Marlin/src/HAL/LPC1768/HAL.h | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 0475c953c3..88a57d7416 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -106,3 +106,8 @@ inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { Clock::delayCycles(x); } + +// Add strcmp_P if missing +#ifndef strcmp_P + #define strcmp_P(a, b) strcmp((a), (b)) +#endif diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 7d2b289f35..162da8b56d 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -221,3 +221,8 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, // Reset source void HAL_clear_reset_source(void); uint8_t HAL_get_reset_source(void); + +// Add strcmp_P if missing +#ifndef strcmp_P + #define strcmp_P(a, b) strcmp((a), (b)) +#endif From 59dfba3bb85e29a116663f6c03d0be1d5e3b3d58 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 25 May 2020 13:37:33 -0700 Subject: [PATCH 0522/1454] Fix GTR CR10_STOCKDISPLAY pins (#18078) --- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 43c4d4279f..d1d0ddc480 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -320,13 +320,13 @@ #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PA8 + #define LCD_PINS_RS PG6 - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define BTN_EN1 PC10 + #define BTN_EN2 PG8 - #define LCD_PINS_ENABLE PG7 - #define LCD_PINS_D4 PG8 + #define LCD_PINS_ENABLE PG5 + #define LCD_PINS_D4 PG7 //#undef ST7920_DELAY_1 //#undef ST7920_DELAY_2 From 8c0c8e40463d2145e8a48fc1e23d4cd86b0a7849 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 25 May 2020 13:42:31 -0700 Subject: [PATCH 0523/1454] 8 Extruders + Graphical LCD fix (#18079) --- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 32 +++++++++++++++++--- buildroot/share/tests/BIGTREE_GTR_V1_0-tests | 1 + 2 files changed, 29 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 1095a97c0e..4ae0bf4ac0 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -1425,8 +1425,14 @@ #ifndef STATUS_HOTEND6_WIDTH #define STATUS_HOTEND6_WIDTH STATUS_HOTEND5_WIDTH #endif + #ifndef STATUS_HOTEND7_WIDTH + #define STATUS_HOTEND7_WIDTH STATUS_HOTEND6_WIDTH + #endif + #ifndef STATUS_HOTEND8_WIDTH + #define STATUS_HOTEND8_WIDTH STATUS_HOTEND7_WIDTH + #endif - constexpr uint8_t status_hotend_width[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_WIDTH, STATUS_HOTEND2_WIDTH, STATUS_HOTEND3_WIDTH, STATUS_HOTEND4_WIDTH, STATUS_HOTEND5_WIDTH, STATUS_HOTEND6_WIDTH); + constexpr uint8_t status_hotend_width[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_WIDTH, STATUS_HOTEND2_WIDTH, STATUS_HOTEND3_WIDTH, STATUS_HOTEND4_WIDTH, STATUS_HOTEND5_WIDTH, STATUS_HOTEND6_WIDTH, STATUS_HOTEND7_WIDTH, STATUS_HOTEND8_WIDTH); #define STATUS_HOTEND_WIDTH(N) status_hotend_width[N] #ifndef STATUS_HOTEND1_BYTEWIDTH @@ -1447,8 +1453,14 @@ #ifndef STATUS_HOTEND6_BYTEWIDTH #define STATUS_HOTEND6_BYTEWIDTH BW(STATUS_HOTEND6_WIDTH) #endif + #ifndef STATUS_HOTEND7_BYTEWIDTH + #define STATUS_HOTEND7_BYTEWIDTH BW(STATUS_HOTEND7_WIDTH) + #endif + #ifndef STATUS_HOTEND8_BYTEWIDTH + #define STATUS_HOTEND8_BYTEWIDTH BW(STATUS_HOTEND8_WIDTH) + #endif - constexpr uint8_t status_hotend_bytewidth[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_BYTEWIDTH, STATUS_HOTEND2_BYTEWIDTH, STATUS_HOTEND3_BYTEWIDTH, STATUS_HOTEND4_BYTEWIDTH, STATUS_HOTEND5_BYTEWIDTH, STATUS_HOTEND6_BYTEWIDTH); + constexpr uint8_t status_hotend_bytewidth[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_BYTEWIDTH, STATUS_HOTEND2_BYTEWIDTH, STATUS_HOTEND3_BYTEWIDTH, STATUS_HOTEND4_BYTEWIDTH, STATUS_HOTEND5_BYTEWIDTH, STATUS_HOTEND6_BYTEWIDTH, STATUS_HOTEND7_BYTEWIDTH, STATUS_HOTEND8_BYTEWIDTH); #define STATUS_HOTEND_BYTEWIDTH(N) status_hotend_bytewidth[N] #ifndef STATUS_HOTEND1_X @@ -1471,8 +1483,14 @@ #ifndef STATUS_HOTEND6_X #define STATUS_HOTEND6_X STATUS_HOTEND5_X + STATUS_HEATERS_XSPACE #endif + #ifndef STATUS_HOTEND7_X + #define STATUS_HOTEND7_X STATUS_HOTEND6_X + STATUS_HEATERS_XSPACE + #endif + #ifndef STATUS_HOTEND8_X + #define STATUS_HOTEND8_X STATUS_HOTEND7_X + STATUS_HEATERS_XSPACE + #endif - constexpr uint8_t status_hotend_x[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_X, STATUS_HOTEND2_X, STATUS_HOTEND3_X, STATUS_HOTEND4_X, STATUS_HOTEND5_X, STATUS_HOTEND6_X); + constexpr uint8_t status_hotend_x[HOTENDS] = ARRAY_N(HOTENDS, STATUS_HOTEND1_X, STATUS_HOTEND2_X, STATUS_HOTEND3_X, STATUS_HOTEND4_X, STATUS_HOTEND5_X, STATUS_HOTEND6_X, STATUS_HOTEND7_X, STATUS_HOTEND8_X); #define STATUS_HOTEND_X(N) status_hotend_x[N] #elif HAS_MULTI_HOTEND #define STATUS_HOTEND_X(N) ((N) ? STATUS_HOTEND2_X : STATUS_HOTEND1_X) @@ -1497,7 +1515,13 @@ #ifndef STATUS_HOTEND6_TEXT_X #define STATUS_HOTEND6_TEXT_X STATUS_HOTEND5_TEXT_X + STATUS_HEATERS_XSPACE #endif - constexpr uint8_t status_hotend_text_x[] = ARRAY_N(HOTENDS, STATUS_HOTEND1_TEXT_X, STATUS_HOTEND2_TEXT_X, STATUS_HOTEND3_TEXT_X, STATUS_HOTEND4_TEXT_X, STATUS_HOTEND5_TEXT_X, STATUS_HOTEND6_TEXT_X); + #ifndef STATUS_HOTEND7_TEXT_X + #define STATUS_HOTEND7_TEXT_X STATUS_HOTEND6_TEXT_X + STATUS_HEATERS_XSPACE + #endif + #ifndef STATUS_HOTEND8_TEXT_X + #define STATUS_HOTEND8_TEXT_X STATUS_HOTEND7_TEXT_X + STATUS_HEATERS_XSPACE + #endif + constexpr uint8_t status_hotend_text_x[] = ARRAY_N(HOTENDS, STATUS_HOTEND1_TEXT_X, STATUS_HOTEND2_TEXT_X, STATUS_HOTEND3_TEXT_X, STATUS_HOTEND4_TEXT_X, STATUS_HOTEND5_TEXT_X, STATUS_HOTEND6_TEXT_X, STATUS_HOTEND7_TEXT_X, STATUS_HOTEND8_TEXT_X); #define STATUS_HOTEND_TEXT_X(N) status_hotend_text_x[N] #else #define STATUS_HOTEND_TEXT_X(N) (STATUS_HOTEND1_X + 6 + (N) * (STATUS_HEATERS_XSPACE)) diff --git a/buildroot/share/tests/BIGTREE_GTR_V1_0-tests b/buildroot/share/tests/BIGTREE_GTR_V1_0-tests index 850aaeacdf..58f6f71fda 100644 --- a/buildroot/share/tests/BIGTREE_GTR_V1_0-tests +++ b/buildroot/share/tests/BIGTREE_GTR_V1_0-tests @@ -23,6 +23,7 @@ opt_set E1_AUTO_FAN_PIN PC11 opt_set E2_AUTO_FAN_PIN PC12 opt_set X_DRIVER_TYPE TMC2208 opt_set Y_DRIVER_TYPE TMC2130 +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER exec_test $1 $2 "BigTreeTech GTR 8 Extruders with Auto-Fan and Mixed TMC Drivers" restore_configs From fe7452c5cbc9086abfdaeac316351cfa17de61c4 Mon Sep 17 00:00:00 2001 From: George Fu Date: Tue, 26 May 2020 04:48:33 +0800 Subject: [PATCH 0524/1454] TMC serial multiplexer, FYSETC AIO-II (#18080) --- Marlin/src/feature/tmc_util.h | 4 ++ Marlin/src/module/stepper/trinamic.cpp | 6 ++- Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h | 44 +++++++++---------- Marlin/src/sd/cardreader.cpp | 2 +- .../PlatformIO/scripts/STM32F103RC_fysetc.py | 22 ++-------- 5 files changed, 36 insertions(+), 42 deletions(-) diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 73e9109ea2..77e4ce517c 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -149,9 +149,13 @@ class TMCMarlin : public TMC220 TMCMarlin(Stream * SerialPort, const float RS, const uint8_t) : TMC2208Stepper(SerialPort, RS) {} + TMCMarlin(Stream * SerialPort, const float RS, uint8_t addr, const uint16_t mul_pin1, const uint16_t mul_pin2) : + TMC2208Stepper(SerialPort, RS, addr, mul_pin1, mul_pin2) + {} TMCMarlin(const uint16_t RX, const uint16_t TX, const float RS, const uint8_t, const bool has_rx=true) : TMC2208Stepper(RX, TX, RS, has_rx) {} + uint16_t rms_current() { return TMC2208Stepper::rms_current(); } inline void rms_current(const uint16_t mA) { this->val_mA = mA; diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index ed238ede7d..26a0f58959 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -49,7 +49,11 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) #endif -#define TMC_UART_HW_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(&ST##_HARDWARE_SERIAL, float(ST##_RSENSE), ST##_SLAVE_ADDRESS) +#if ENABLED(TMC_SERIAL_MULTIPLEXER) + #define TMC_UART_HW_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(&ST##_HARDWARE_SERIAL, float(ST##_RSENSE), ST##_SLAVE_ADDRESS, SERIAL_MUL_PIN1, SERIAL_MUL_PIN2) +#else + #define TMC_UART_HW_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(&ST##_HARDWARE_SERIAL, float(ST##_RSENSE), ST##_SLAVE_ADDRESS) +#endif #define TMC_UART_SW_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_SERIAL_RX_PIN, ST##_SERIAL_TX_PIN, float(ST##_RSENSE), ST##_SLAVE_ADDRESS, ST##_SERIAL_RX_PIN > -1) #define _TMC_SPI_DEFINE(IC, ST, AI) __TMC_SPI_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index 187aec7636..fc9cfd6a7c 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -30,7 +30,7 @@ #define DISABLE_JTAG -#define pins_v2_20190128 // geo-f:add for new pins define +#define pins_v2_20190128 // new pins define // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 @@ -84,32 +84,32 @@ #define E0_DIR_PIN PC14 #define E0_ENABLE_PIN PC13 +#if HAS_TMC220x + + /** + * TMC2208/TMC2209 stepper drivers + */ + + // + // Hardware serial with switch + // + #define X_HARDWARE_SERIAL Serial1 + #define Y_HARDWARE_SERIAL Serial1 + #define Z_HARDWARE_SERIAL Serial1 + #define E0_HARDWARE_SERIAL Serial1 + #define TMC_SERIAL_MULTIPLEXER + #define SERIAL_MUL_PIN1 PB13 + #define SERIAL_MUL_PIN2 PB12 + +#endif + // // Stepper current PWM // - -// X:PA2 Y:PA3 Z:PB12 E:PB13 // changed for test -//#define MOTOR_CURRENT_PWM_XY_PIN PA3 -//#define MOTOR_CURRENT_PWM_Z_PIN PA2 // PB12 -//#define MOTOR_CURRENT_PWM_XY_PIN PB6 -//#define MOTOR_CURRENT_PWM_Z_PIN PB7 // PB12 -//#define MOTOR_CURRENT_PWM_E_PIN -1 // PB13 -// Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE - #define MOTOR_CURRENT_PWM_RANGE 1500 // geo-f:old 2000 + #define MOTOR_CURRENT_PWM_RANGE 1500 // origin:2000 #endif -#define DEFAULT_PWM_MOTOR_CURRENT {500, 500, 400} // geo-f:old 1300 1300 1250 - -// 采用 SDIO PCB从左到右数 -// 1:PC10 - SDIO_D2 -// 2:PC11 - SDIO_D3 -// 3:PD2 - SDIO_CMD -// 4:VCC -// 5:PC12 - SDIO_CK -// 6:VDD -// 7:PC8 - SDIO_D0 -// 8:PC9 - SDIO_D1 -// 9:PA15 - SD_DETECT_PIN +#define DEFAULT_PWM_MOTOR_CURRENT { 500, 500, 400 } // origin: {1300,1300,1250} // // Heaters / Fans diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 54a17f57aa..7b4b74915e 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -393,7 +393,7 @@ void CardReader::manage_media() { if (stat) { // Media Inserted safe_delay(500); // Some boards need a delay to get settled mount(); // Try to mount the media - #if MB(FYSETC_CHEETAH) + #if MB(FYSETC_CHEETAH, FYSETC_AIO_II) reset_stepper_drivers(); // Workaround for Cheetah bug #endif if (!isMounted()) stat = 0; // Not mounted? diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 67a75f5b47..134f63d668 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -2,7 +2,10 @@ from os.path import join from os.path import expandvars Import("env", "projenv") -# Relocate firmware from 0x08000000 to 0x08002000 +# Relocate firmware from 0x08000000 to 0x08010000 +# for define in env['CPPDEFINES']: +# if define[0] == "VECT_TAB_ADDR": +# env['CPPDEFINES'].remove(define) #env['CPPDEFINES'].remove(("VECT_TAB_ADDR", 134217728)) #env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08010000")) @@ -14,14 +17,6 @@ env.AddPostAction( "\"" + join("$BUILD_DIR","${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path ]), "Building $TARGET")) -# please keep $SOURCE variable, it will be replaced with a path to firmware - -# Generic -#env.Replace( -# UPLOADER="serial_upload.bat" -# UPLOADCMD="$UPLOADER stm32loader.py $SOURCE" -#) - # In-line command with arguments UPLOAD_TOOL="stm32flash" platform = env.PioPlatform() @@ -32,12 +27,3 @@ env.Replace( UPLOADER=UPLOAD_TOOL, UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr -R -b 115200 -g 0x8000000 -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"" + " $UPLOAD_PORT") ) - -# Python callback -#def on_upload(source, target, env): -# print source, target -# firmware_path = str(source[0]) -# # do something -# env.Execute(".\serial_upload.bat") - -#env.Replace(UPLOADCMD=on_upload) From 7d7f58c3e3e2ddb633ea81e67aa55ed7ac646d84 Mon Sep 17 00:00:00 2001 From: grauerfuchs <42082416+grauerfuchs@users.noreply.github.com> Date: Mon, 25 May 2020 17:24:50 -0400 Subject: [PATCH 0525/1454] Fix Mightyboard PIO env (#18098) --- platformio.ini | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/platformio.ini b/platformio.ini index 413b5201da..9d7da43fba 100644 --- a/platformio.ini +++ b/platformio.ini @@ -86,6 +86,7 @@ board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip src_filter = ${common.default_src_filter} + +upload_speed = 57600 # # MightyBoard ATmega2560 (MegaCore 100 pin boards variants) @@ -97,6 +98,9 @@ board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip src_filter = ${common.default_src_filter} + +upload_protocol = wiring +upload_speed = 57600 +board_upload.maximum_size = 253952 # # RAMBo From de89a4b7c1f78e16ea3ed706ea97760ffb1523c8 Mon Sep 17 00:00:00 2001 From: invalidflaw <36581852+invalidflaw@users.noreply.github.com> Date: Mon, 25 May 2020 17:09:38 -0500 Subject: [PATCH 0526/1454] Add PICA Servo / E1 pins (#18100) --- Marlin/src/pins/mega/pins_PICA.h | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 506ce242c5..69974773ee 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -46,6 +46,12 @@ #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif +// +// Servos +// +#define SERVO0_PIN 3 +#define SERVO1_PIN 4 +#define SERVO2_PIN 5 // // Limit Switches // @@ -75,6 +81,10 @@ #define E0_DIR_PIN 24 #define E0_ENABLE_PIN 26 +#define E1_STEP_PIN 68 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 27 + // // Temperature Sensors // From f776260d7aaf47e54967870effc44a55fa4001bd Mon Sep 17 00:00:00 2001 From: "g3gg0.de" Date: Tue, 26 May 2020 00:14:15 +0200 Subject: [PATCH 0527/1454] Fix OCR / PWM calculation (#18094) Fixes #17968 --- Marlin/src/HAL/AVR/fast_pwm.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index e855057486..e96ca3246b 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -274,7 +274,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 else top = *timer.ICRn; // top = ICRn - _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top / v_size)); // Scale 8/16-bit v to top value + _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top) / float(v_size)); // Scale 8/16-bit v to top value } } From 5fbea83840dd947790128ec19fab90da29679d20 Mon Sep 17 00:00:00 2001 From: XDA-Bam <1209896+XDA-Bam@users.noreply.github.com> Date: Tue, 26 May 2020 00:29:02 +0200 Subject: [PATCH 0528/1454] Explicitly optimize x/x in Classic Jerk (#18112) Can we outsmart the compiler? --- Marlin/src/module/planner.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 6058486510..38442d7b96 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2456,16 +2456,16 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting. CACHED_SQRT(previous_nominal_speed, previous_nominal_speed_sqr); - vmax_junction = _MIN(nominal_speed, previous_nominal_speed); + float smaller_speed_factor = 1.0f; + if (nominal_speed < previous_nominal_speed) { + vmax_junction = nominal_speed; + smaller_speed_factor = vmax_junction / previous_nominal_speed; + } + else + vmax_junction = previous_nominal_speed; // Now limit the jerk in all axes. - const float smaller_speed_factor = vmax_junction / previous_nominal_speed; - #if HAS_LINEAR_E_JERK - LOOP_XYZ(axis) - #else - LOOP_XYZE(axis) - #endif - { + TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(axis) { // Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop. float v_exit = previous_speed[axis] * smaller_speed_factor, v_entry = current_speed[axis]; From f3bf343c89a1452af92fa7f57f3a4eb2761c77a8 Mon Sep 17 00:00:00 2001 From: Gurmeet Athwal Date: Tue, 26 May 2020 04:16:35 +0530 Subject: [PATCH 0529/1454] Report fan speed on change (#18013) --- Marlin/src/module/temperature.cpp | 10 ++++++++++ Marlin/src/module/temperature.h | 1 + 2 files changed, 11 insertions(+) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 6121a5a0ac..264d0a9039 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -204,6 +204,16 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, if (target >= FAN_COUNT) return; fan_speed[target] = speed; + report_fan_speed(target); + } + + /** + * Report print fan speed for a target extruder + */ + void Temperature::report_fan_speed(const uint8_t target) { + if (target >= FAN_COUNT) return; + PORT_REDIRECT(SERIAL_BOTH); + SERIAL_ECHOLNPAIR("M106 P", target, " S", fan_speed[target]); } #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index b2c5497b00..8f875f84f3 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -483,6 +483,7 @@ class Temperature { #define FANS_LOOP(I) LOOP_L_N(I, FAN_COUNT) static void set_fan_speed(const uint8_t target, const uint16_t speed); + static void report_fan_speed(const uint8_t target); #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) static bool fans_paused; From 5fefecc5268f596ded2154ae323249c003e5d934 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 25 May 2020 16:24:16 -0700 Subject: [PATCH 0530/1454] Use 'extends' for STM32F1, fix lib versions (#18099) --- platformio.ini | 297 ++++++++++++++++++------------------------------- 1 file changed, 110 insertions(+), 187 deletions(-) diff --git a/platformio.ini b/platformio.ini index 9d7da43fba..350095e37f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -27,15 +27,35 @@ extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-cxxflags.py build_flags = -fmax-errors=5 -g -D__MARLIN_FIRMWARE__ -fmerge-all-constants lib_deps = LiquidCrystal - TMCStepper@>=0.6.2,<1.0.0 + TMCStepper@>=0.6.2 + Adafruit MAX31865 library Adafruit NeoPixel U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip - Adafruit_MAX31865=https://github.com/adafruit/Adafruit_MAX31865/archive/master.zip LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/0.8.0.zip SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip SlowSoftI2CMaster=https://github.com/mikeshub/SlowSoftI2CMaster/archive/master.zip +[common_stm32f1] +platform = ststm32 +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py + ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL +build_unflags = -std=gnu++11 +src_filter = ${common.default_src_filter} + +lib_ignore = + Adafruit NeoPixel + SPI +lib_deps = + LiquidCrystal + TMCStepper@>=0.6.2 + U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip + Adafruit MAX31865 library@>=1.1,<1.2 + LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip + Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/0.8.0.zip + SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip + SlowSoftI2CMaster=https://github.com/mikeshub/SlowSoftI2CMaster/archive/master.zip + SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + # Globally defined properties # inherited by all environments [env] @@ -296,34 +316,20 @@ lib_deps = Servo # STM32F103RC # [env:STM32F103RC] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103RC platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 # # STM32F103RC_fysetc # [env:STM32F103RC_fysetc] -platform = ststm32 -board = genericSTM32F103RC -#board_build.core = maple -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DDEBUG_LEVEL=0 -DHAVE_SW_SERIAL -build_unflags = -std=gnu++11 +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 lib_ldf_mode = chain debug_tool = stlink upload_protocol = serial @@ -338,79 +344,41 @@ upload_protocol = serial # [env:STM32F103RC_btt] -platform = ststm32 -board = genericSTM32F103RC -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -build_unflags = -std=gnu++11 +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 monitor_speed = 115200 [env:STM32F103RC_btt_USB] -platform = ststm32 -board = genericSTM32F103RC -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DUSE_USB_COMPOSITE -build_unflags = -std=gnu++11 -extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt +build_flags = ${env:STM32F103RC_btt.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${env:STM32F103RC_btt.lib_deps} USBComposite for STM32F1@==0.91 -lib_ignore = Adafruit NeoPixel, SPI -monitor_speed = 115200 [env:STM32F103RC_btt_512K] -platform = ststm32 -board = genericSTM32F103RC +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt board_upload.maximum_size=524288 -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_FLASH_SIZE=512 -build_unflags = -std=gnu++11 -extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI -monitor_speed = 115200 +build_flags = ${env:STM32F103RC_btt.build_flags} -DSTM32_FLASH_SIZE=512 [env:STM32F103RC_btt_512K_USB] -platform = ststm32 -board = genericSTM32F103RC -board_upload.maximum_size=524288 -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_FLASH_SIZE=512 -DUSE_USB_COMPOSITE -build_unflags = -std=gnu++11 -extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt_512K +build_flags = ${env:STM32F103RC_btt_512K.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${env:STM32F103RC_btt_512K.lib_deps} USBComposite for STM32F1@==0.91 -lib_ignore = Adafruit NeoPixel, SPI -monitor_speed = 115200 # # STM32F103RE # [env:STM32F103RE] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103RE platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 # @@ -418,37 +386,19 @@ monitor_speed = 115200 # STM32F103RE_btt_USB ......... RET6 (USB mass storage) # [env:STM32F103RE_btt] -platform = ststm32 -board = genericSTM32F103RE -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -build_unflags = -std=gnu++11 +platform = ${common_stm32f1.platform} +extends = env:STM32F103RE extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 debug_tool = stlink upload_protocol = stlink -monitor_speed = 115200 [env:STM32F103RE_btt_USB] -platform = ststm32 -board = genericSTM32F103RE -platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DUSE_USB_COMPOSITE -build_unflags = -std=gnu++11 -extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +platform = ${common_stm32f1.platform} +extends = env:STM32F103RE_btt +build_flags = ${env:STM32F103RE_btt.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${common_stm32f1.lib_deps} USBComposite for STM32F1@==0.91 -lib_ignore = Adafruit NeoPixel, SPI -debug_tool = stlink -upload_protocol = stlink -monitor_speed = 115200 # # STM32F4 with STM32GENERIC @@ -488,156 +438,129 @@ src_filter = ${common.default_src_filter} + # Geeetech GTM32 (STM32F103VET6) # [env:STM32F103VE_GTM32] -platform = ststm32 -board = genericSTM32F103VE -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -ffunction-sections -fdata-sections -nostdlib -MMD +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +build_flags = ${common_stm32f1.build_flags} + -ffunction-sections -fdata-sections -nostdlib -MMD -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v - -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel, SPI + -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 + -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 upload_protocol = serial # # Longer 3D board in Alfawise U20 (STM32F103VET6) # [env:STM32F103VE_longer] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103VE -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 -build_unflags = -std=gnu++11 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py -src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel, LiquidTWI2, SPI +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 +build_unflags = ${common_stm32f1.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +lib_ignore = ${common_stm32f1.lib_ignore} + LiquidTWI2 # # MKS Robin Mini (STM32F103VET6) # [env:mks_robin_mini] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103VE -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DMCU_STM32F103VE -build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_mini.py -src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE # # MKS Robin Nano (STM32F103VET6) # [env:mks_robin_nano] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103VE platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DMCU_STM32F103VE -DHAVE_SW_SERIAL -DSS_TIMER=4 -build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_nano.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 + # # MKS Robin (STM32F103ZET6) # [env:mks_robin] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103ZE -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_XL_DENSITY -build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} + -DSS_TIMER=4 -DSTM32_XL_DENSITY # # MKS Robin Pro (STM32F103ZET6) # [env:mks_robin_pro] -platform = ststm32 -board = genericSTM32F103ZE +platform = ${common_stm32f1.platform} +extends = env:mks_robin extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_pro.py -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_XL_DENSITY -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI # # MKS Robin E3D (STM32F103RCT6) and # MKS Robin E3 with TMC2209 # [env:mks_robin_e3] -platform = ststm32 -board = genericSTM32F103RC +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -build_unflags = -std=gnu++11 -extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_e3.py -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip -lib_ignore = Adafruit NeoPixel, SPI +extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_e3.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 # # MKS Robin Lite/Lite2 (STM32F103RCT6) # [env:mks_robin_lite] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103RC -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_lite.py -src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel, SPI + # # MKS ROBIN LITE3 (STM32F103RCT6) # [env:mks_robin_lite3] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103RC extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_lite3.py -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -std=gnu++14 -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} -lib_ignore = Adafruit NeoPixel, SPI # # JGAurora A5S A1 (STM32F103ZET6) # [env:jgaurora_a5s_a1] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103ZE -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DSTM32F1xx -std=gnu++14 -DSTM32_XL_DENSITY -build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py -src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel, SPI +build_flags = ${common_stm32f1.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY # # Malyan M200 (STM32F103CB) # [env:STM32F103CB_malyan] -platform = ststm32 -board = malyanM200 -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections - -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ -src_filter = ${common.default_src_filter} + -lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-HAL, SPI +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = malyanM200 +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections + -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ +lib_ignore = ${common_stm32f1.lib_ignore} + LiquidCrystal, LiquidTWI2, TMCStepper, U8glib-HAL, SoftwareSerialM # # Malyan M200 v2 (STM32F070RB) @@ -669,14 +592,14 @@ lib_ignore = LiquidCrystal, LiquidTWI2, Adafruit NeoPixel, TMCStepper, U8glib-H # Chitu boards like Tronxy X5s (STM32F103ZET6) # [env:chitu_f103] -platform = ststm32 +platform = ${common_stm32f1.platform} +extends = common_stm32f1 board = genericSTM32F103ZE -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DSTM32F1xx -std=gnu++14 -DSTM32_XL_DENSITY -build_unflags = -std=gnu++11 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 extra_scripts = buildroot/share/PlatformIO/scripts/chitu_crypt.py -src_filter = ${common.default_src_filter} + -lib_ignore = Adafruit NeoPixel +build_flags = ${common_stm32f1.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY +build_unflags = ${common_stm32f1.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 # # STM32F401VE From f402ab7afb8bf7b9989bf0b75769be30c302d921 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 25 May 2020 16:39:51 -0700 Subject: [PATCH 0531/1454] Limit MAX31865 library to <1.2 (#18089) --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index 350095e37f..416d21f82f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -28,7 +28,7 @@ build_flags = -fmax-errors=5 -g -D__MARLIN_FIRMWARE__ -fmerge-all-constants lib_deps = LiquidCrystal TMCStepper@>=0.6.2 - Adafruit MAX31865 library + Adafruit MAX31865 library@>=1.1,<1.2 Adafruit NeoPixel U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip From 8b320f909541dcb9bf770a32628450f9865f4718 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 26 May 2020 00:07:25 +0000 Subject: [PATCH 0532/1454] [cron] Bump distribution date (2020-05-26) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ca402935a4..5d6fe871e2 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-25" + #define STRING_DISTRIBUTION_DATE "2020-05-26" #endif /** From 38ccc769f79844f1e44be5167b060a5af5cc4937 Mon Sep 17 00:00:00 2001 From: rudihorn Date: Tue, 26 May 2020 06:43:29 +0100 Subject: [PATCH 0533/1454] Emergency Parser for STM32 (#18095) --- Marlin/src/HAL/STM32/HAL.cpp | 3 + Marlin/src/HAL/STM32/HAL.h | 37 ++++++------ Marlin/src/HAL/STM32/MarlinSerial.cpp | 80 ++++++++++++++++++++++++++ Marlin/src/HAL/STM32/MarlinSerial.h | 54 +++++++++++++++++ Marlin/src/HAL/STM32/inc/SanityCheck.h | 4 -- Marlin/src/HAL/STM32/usb_serial.cpp | 55 ++++++++++++++++++ Marlin/src/HAL/STM32/usb_serial.h | 21 +++++++ 7 files changed, 232 insertions(+), 22 deletions(-) create mode 100644 Marlin/src/HAL/STM32/MarlinSerial.cpp create mode 100644 Marlin/src/HAL/STM32/MarlinSerial.h create mode 100644 Marlin/src/HAL/STM32/usb_serial.cpp create mode 100644 Marlin/src/HAL/STM32/usb_serial.h diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 37cfb576d1..c09592a564 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -23,6 +23,7 @@ #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "HAL.h" +#include "usb_serial.h" #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" @@ -79,6 +80,8 @@ void HAL_init() { #endif SetSoftwareSerialTimerInterruptPriority(); + + TERN_(EMERGENCY_PARSER, USB_Hook_init()); } void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 4c64d95153..3319636704 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -30,6 +30,7 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" #include "watchdog.h" +#include "MarlinSerial.h" #include "../../inc/MarlinConfigPre.h" @@ -48,17 +49,17 @@ #elif SERIAL_PORT == -1 #define MYSERIAL0 SerialUSB #elif SERIAL_PORT == 1 - #define MYSERIAL0 Serial1 + #define MYSERIAL0 MSerial1 #elif SERIAL_PORT == 2 - #define MYSERIAL0 Serial2 + #define MYSERIAL0 MSerial2 #elif SERIAL_PORT == 3 - #define MYSERIAL0 Serial3 + #define MYSERIAL0 MSerial3 #elif SERIAL_PORT == 4 - #define MYSERIAL0 Serial4 + #define MYSERIAL0 MSerial4 #elif SERIAL_PORT == 5 - #define MYSERIAL0 Serial5 + #define MYSERIAL0 MSerial5 #elif SERIAL_PORT == 6 - #define MYSERIAL0 Serial6 + #define MYSERIAL0 MSerial6 #else #error "SERIAL_PORT must be from -1 to 6. Please update your configuration." #endif @@ -72,17 +73,17 @@ #elif SERIAL_PORT_2 == -1 #define MYSERIAL1 SerialUSB #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 Serial1 + #define MYSERIAL1 MSerial1 #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 Serial2 + #define MYSERIAL1 MSerial2 #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 Serial3 + #define MYSERIAL1 MSerial3 #elif SERIAL_PORT_2 == 4 - #define MYSERIAL1 Serial4 + #define MYSERIAL1 MSerial4 #elif SERIAL_PORT_2 == 5 - #define MYSERIAL1 Serial5 + #define MYSERIAL1 MSerial5 #elif SERIAL_PORT_2 == 6 - #define MYSERIAL1 Serial6 + #define MYSERIAL1 MSerial6 #else #error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration." #endif @@ -100,17 +101,17 @@ #elif DGUS_SERIAL_PORT == -1 #define DGUS_SERIAL SerialUSB #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL Serial1 + #define DGUS_SERIAL MSerial1 #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL Serial2 + #define DGUS_SERIAL MSerial2 #elif DGUS_SERIAL_PORT == 3 - #define DGUS_SERIAL Serial3 + #define DGUS_SERIAL MSerial3 #elif DGUS_SERIAL_PORT == 4 - #define DGUS_SERIAL Serial4 + #define DGUS_SERIAL MSerial4 #elif DGUS_SERIAL_PORT == 5 - #define DGUS_SERIAL Serial5 + #define DGUS_SERIAL MSerial5 #elif DGUS_SERIAL_PORT == 6 - #define DGUS_SERIAL Serial6 + #define DGUS_SERIAL MSerial6 #else #error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration." #endif diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp new file mode 100644 index 0000000000..1961791e22 --- /dev/null +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) + +#include "../../inc/MarlinConfig.h" +#include "MarlinSerial.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +#define DECLARE_SERIAL_PORT(ser_num) \ + void _rx_complete_irq_ ## ser_num (serial_t * obj); \ + MarlinSerial MSerial ## ser_num (USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ + void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); } + +#define DECLARE_SERIAL_PORT_EXP(ser_num) DECLARE_SERIAL_PORT(ser_num) + +#if defined(SERIAL_PORT) && SERIAL_PORT >= 0 + DECLARE_SERIAL_PORT_EXP(SERIAL_PORT) +#endif + +#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 + DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2) +#endif + +#if defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT >= 0 + DECLARE_SERIAL_PORT_EXP(DGUS_SERIAL_PORT) +#endif + +void MarlinSerial::begin(unsigned long baud, uint8_t config) { + HardwareSerial::begin(baud, config); + // replace the IRQ callback with the one we have defined + #if ENABLED(EMERGENCY_PARSER) + _serial.rx_callback = _rx_callback; + #endif +} + +// This function is Copyright (c) 2006 Nicholas Zambetti. +void MarlinSerial::_rx_complete_irq(serial_t *obj) { + // No Parity error, read byte and store it in the buffer if there is room + unsigned char c; + + if (uart_getc(obj, &c) == 0) { + + rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE; + + // if we should be storing the received character into the location + // just before the tail (meaning that the head would advance to the + // current location of the tail), we're about to overflow the buffer + // and so we don't write the character or advance the head. + if (i != obj->rx_tail) { + obj->rx_buff[obj->rx_head] = c; + obj->rx_head = i; + } + + #if ENABLED(EMERGENCY_PARSER) + emergency_parser.update(emergency_state, c); + #endif + } +} + +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h new file mode 100644 index 0000000000..290fdce9ee --- /dev/null +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +typedef void (*usart_rx_callback_t)(serial_t * obj); + +class MarlinSerial : public HardwareSerial { +public: + MarlinSerial(void* peripheral, usart_rx_callback_t rx_callback) : + HardwareSerial(peripheral), _rx_callback(rx_callback) + #if ENABLED(EMERGENCY_PARSER) + , emergency_state(EmergencyParser::State::EP_RESET) + #endif + { } + + void begin(unsigned long baud, uint8_t config); + inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + + void _rx_complete_irq(serial_t* obj); + +protected: + usart_rx_callback_t _rx_callback; + #if ENABLED(EMERGENCY_PARSER) + EmergencyParser::State emergency_state; + #endif +}; + +extern MarlinSerial MSerial1; +extern MarlinSerial MSerial2; +extern MarlinSerial MSerial3; +extern MarlinSerial MSerial4; +extern MarlinSerial MSerial5; diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 7734fc0e83..7236b7f4ed 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -28,10 +28,6 @@ // #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" //#endif -#if ENABLED(EMERGENCY_PARSER) - #error "EMERGENCY_PARSER is not yet implemented for STM32. Disable EMERGENCY_PARSER to continue." -#endif - #if ENABLED(FAST_PWM_FAN) #error "FAST_PWM_FAN is not yet implemented for this platform." #endif diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp new file mode 100644 index 0000000000..86c164cb93 --- /dev/null +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(EMERGENCY_PARSER) + +#include "usb_serial.h" +#include "../../feature/e_parser.h" + +EmergencyParser::State emergency_state = EmergencyParser::State::EP_RESET; + +int8_t (*USBD_CDC_Receive_original) (uint8_t *Buf, uint32_t *Len) = nullptr; + +static int8_t USBD_CDC_Receive_hook(uint8_t *Buf, uint32_t *Len) { + for (uint32_t i = 0; i < *Len; i++) + emergency_parser.update(emergency_state, Buf[i]); + return USBD_CDC_Receive_original(Buf, Len); +} + +typedef struct _USBD_CDC_Itf { + int8_t (* Init)(void); + int8_t (* DeInit)(void); + int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length); + int8_t (* Receive)(uint8_t *Buf, uint32_t *Len); + int8_t (* Transferred)(void); +} USBD_CDC_ItfTypeDef; + +extern USBD_CDC_ItfTypeDef USBD_CDC_fops; + +void USB_Hook_init() { + USBD_CDC_Receive_original = USBD_CDC_fops.Receive; + USBD_CDC_fops.Receive = USBD_CDC_Receive_hook; +} + +#endif // EMERGENCY_PARSER +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/usb_serial.h b/Marlin/src/HAL/STM32/usb_serial.h new file mode 100644 index 0000000000..4243683479 --- /dev/null +++ b/Marlin/src/HAL/STM32/usb_serial.h @@ -0,0 +1,21 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +void USB_Hook_init(); From 6c994002af1ef13004490b5e15501e6cdc70dd88 Mon Sep 17 00:00:00 2001 From: Bob Kuhn Date: Tue, 26 May 2020 00:44:12 -0500 Subject: [PATCH 0534/1454] No SD_CHECK_AND_RETRY with USE_USB_COMPOSITE (STM32F103 + SDIO) (#18108) * disable SD_CHECK_AND_RETRY when USE_USB_COMPOSITE is enabled * Update Sd2Card.cpp * Disable SD_CHECK_AND_RETRY with USE_USB_COMPOSITE Co-authored-by: Scott Lahteine Co-authored-by: Scott Lahteine --- Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h | 5 +++++ Marlin/src/sd/Sd2Card.cpp | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h index 0285c52ee3..4e3b8903dd 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h @@ -20,3 +20,8 @@ * */ #pragma once + +#if ENABLED(USE_USB_COMPOSITE) + //#warning "SD_CHECK_AND_RETRY isn't needed with USE_USB_COMPOSITE." + #undef SD_CHECK_AND_RETRY +#endif diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index ba233d36f6..e21662afc1 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -575,7 +575,7 @@ bool Sd2Card::writeData(const uint8_t* src) { // Send one block of data for write block or write multiple blocks bool Sd2Card::writeData(const uint8_t token, const uint8_t* src) { - uint16_t crc = + const uint16_t crc = #if ENABLED(SD_CHECK_AND_RETRY) CRC_CCITT(src, 512) #else From 094bf400633b426b4bccec5c5f554c498b56de73 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 27 May 2020 00:07:59 +0000 Subject: [PATCH 0535/1454] [cron] Bump distribution date (2020-05-27) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5d6fe871e2..4cea97887c 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-26" + #define STRING_DISTRIBUTION_DATE "2020-05-27" #endif /** From a49319f3dd508add96b1b057782d42a601aa4bba Mon Sep 17 00:00:00 2001 From: Chris Pepper Date: Wed, 27 May 2020 17:06:32 +0100 Subject: [PATCH 0536/1454] Fix FYSETC_AIO_II build (#18124) BOARD_FYSETC_AIO_II also needs this header for the reset_stepper_drivers function --- Marlin/src/sd/cardreader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 7b4b74915e..7be69beb91 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -378,7 +378,7 @@ void CardReader::mount() { /** * Handle SD card events */ -#if MB(FYSETC_CHEETAH) +#if MB(FYSETC_CHEETAH, FYSETC_AIO_II) #include "../module/stepper.h" #endif From 3bf0d8d1617cd2cf088499963e49662a3fd9c2fd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 27 May 2020 13:12:08 -0500 Subject: [PATCH 0537/1454] Allow disable of LCD click --- Marlin/src/inc/Conditionals_post.h | 3 +++ Marlin/src/lcd/ultralcd.cpp | 15 ++++++--------- Marlin/src/lcd/ultralcd.h | 12 ++++++------ 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 70601c3158..3a8bee4087 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1882,6 +1882,9 @@ #endif #if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) #define HAS_BUZZER 1 + #if LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ + #define HAS_CHIRP 1 + #endif #endif #if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) #define USE_BEEPER 1 diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 12c005a918..753f8a5b48 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -612,15 +612,12 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { UNUSED(clear_buttons); #endif - #if HAS_BUZZER - // Buzz and wait. Is the delay needed for buttons to settle? - buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ); - #if HAS_LCD_MENU - #if USE_BEEPER - for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } - #else - delay(10); - #endif + #if HAS_CHIRP + chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); #endif #endif } diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index b5e1696239..619b9baf27 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -398,6 +398,12 @@ public: static millis_t next_filament_display; #endif + FORCE_INLINE static void chirp() { + #if HAS_CHIRP + buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ); + #endif + } + static void quick_feedback(const bool clear_buttons=true); #if HAS_BUZZER static void completion_feedback(const bool good=true); @@ -524,12 +530,6 @@ public: static void reselect_last_file(); #endif - #if ENABLED(G26_MESH_VALIDATION) - FORCE_INLINE static void chirp() { - TERN_(HAS_BUZZER, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); - } - #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) static void ubl_plot(const uint8_t x_plot, const uint8_t y_plot); #endif From 4724af1011010d6efe273688e2aca523b8c083b4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 27 May 2020 13:38:37 -0500 Subject: [PATCH 0538/1454] Better home for 'chirp' --- Marlin/src/lcd/ultralcd.h | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 619b9baf27..b17e11086f 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -267,6 +267,10 @@ public: static void buzz(const long duration, const uint16_t freq); #endif + FORCE_INLINE static void chirp() { + TERN_(HAS_CHIRP, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); + } + #if ENABLED(LCD_HAS_STATUS_INDICATORS) static void update_indicators(); #endif @@ -398,12 +402,6 @@ public: static millis_t next_filament_display; #endif - FORCE_INLINE static void chirp() { - #if HAS_CHIRP - buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ); - #endif - } - static void quick_feedback(const bool clear_buttons=true); #if HAS_BUZZER static void completion_feedback(const bool good=true); From 84c43e9ee799bdbaa1e5d53f73b63cca85a57d40 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 27 May 2020 13:45:46 -0500 Subject: [PATCH 0539/1454] Fix test comments --- buildroot/share/tests/mega2560-tests | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index ed5713eff8..32be906c9e 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -95,10 +95,10 @@ opt_add M100_FREE_MEMORY_DUMPER opt_add M100_FREE_MEMORY_CORRUPTOR opt_set PWM_MOTOR_CURRENT "{ 1300, 1300, 1250 }" opt_set I2C_SLAVE_ADDRESS 63 -exec_test $1 $2 "MEGACONTROLLER | Ultimaker LCD | M100 | PWM_MOTOR_CURRENT | PRINTCOUNTER | Advanced Pause ..." +exec_test $1 $2 "MEGACONTROLLER | Minipanel | M100 | PWM_MOTOR_CURRENT | PRINTCOUNTER | Advanced Pause ..." # -# Mixing Extruder with 5 steppers, Cyrillic +# Mixing Extruder with 5 steppers, Greek # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO @@ -106,7 +106,7 @@ opt_set LCD_LANGUAGE el_gr opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY opt_set MIXING_STEPPERS 5 opt_set LCD_LANGUAGE ru -exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Cyrillic" +exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" # # Test SPEAKER with BOARD_BQ_ZUM_MEGA_3D and BQ_LCD_SMART_CONTROLLER From 11ef4833f8ac68aae62b218c1cbcf03c344ab460 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 28 May 2020 00:08:57 +0000 Subject: [PATCH 0540/1454] [cron] Bump distribution date (2020-05-28) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4cea97887c..ddc99e648b 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-27" + #define STRING_DISTRIBUTION_DATE "2020-05-28" #endif /** From a740b6b3180f2407dec41f944faf69b8f2100615 Mon Sep 17 00:00:00 2001 From: ellensp Date: Fri, 29 May 2020 05:52:13 +1200 Subject: [PATCH 0541/1454] More 'extend'ed environments (#18118) Co-authored-by: Scott Lahteine --- platformio.ini | 192 ++++++++++++++++++++----------------------------- 1 file changed, 79 insertions(+), 113 deletions(-) diff --git a/platformio.ini b/platformio.ini index 416d21f82f..aa8dd21983 100644 --- a/platformio.ini +++ b/platformio.ini @@ -56,6 +56,12 @@ lib_deps = SlowSoftI2CMaster=https://github.com/mikeshub/SlowSoftI2CMaster/archive/master.zip SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +[common_avr8] +board_build.f_cpu = 16000000L +lib_deps = ${common.lib_deps} + TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip +src_filter = ${common.default_src_filter} + + # Globally defined properties # inherited by all environments [env] @@ -78,112 +84,85 @@ monitor_speed = 250000 # ATmega2560 # [env:mega2560] -platform = atmelavr -board = megaatmega2560 -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +platform = atmelavr +extends = common_avr8 +board = megaatmega2560 # # ATmega1280 # [env:mega1280] -platform = atmelavr -board = megaatmega1280 -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +platform = atmelavr +extends = common_avr8 +board = megaatmega1280 # # MightyBoard ATmega2560 (MegaCore 100 pin boards variants) # [env:MightyBoard1280] -platform = atmelavr -board = ATmega1280 -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + -upload_speed = 57600 +platform = atmelavr +extends = common_avr8 +board = megaatmega1280 +upload_speed = 57600 # # MightyBoard ATmega2560 (MegaCore 100 pin boards variants) # [env:MightyBoard2560] -platform = atmelavr -board = ATmega2560 -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + -upload_protocol = wiring -upload_speed = 57600 +platform = atmelavr +extends = common_avr8 +board = megaatmega2560 +upload_protocol = wiring +upload_speed = 57600 board_upload.maximum_size = 253952 # # RAMBo # [env:rambo] -platform = atmelavr -board = reprap_rambo -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +platform = atmelavr +extends = common_avr8 +board = reprap_rambo # # FYSETC F6 V1.3 # [env:FYSETC_F6_13] -platform = atmelavr -board = fysetc_f6_13 -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +platform = atmelavr +extends = common_avr8 +board = fysetc_f6_13 # # FYSETC F6 V1.4 # [env:FYSETC_F6_14] -platform = atmelavr -board = fysetc_f6_14 -board_build.f_cpu = 16000000L -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +platform = atmelavr +extends = common_avr8 +board = fysetc_f6_14 # # Sanguinololu (ATmega644p) # [env:sanguino644p] platform = atmelavr +extends = common_avr8 board = sanguino_atmega644p -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + # # Sanguinololu (ATmega1284p) # [env:sanguino1284p] platform = atmelavr +extends = common_avr8 board = sanguino_atmega1284p -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + # # Melzi and clones (ATmega1284p) # [env:melzi] platform = atmelavr +extends = common_avr8 board = sanguino_atmega1284p -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + lib_ignore = TMCStepper upload_speed = 57600 @@ -192,11 +171,7 @@ upload_speed = 57600 # [env:melzi_optiboot] platform = atmelavr -board = sanguino_atmega1284p -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + -lib_ignore = TMCStepper +extends = env:melzi upload_speed = 115200 # @@ -208,11 +183,9 @@ upload_speed = 115200 # [env:at90usb1286_cdc] platform = teensy +extends = common_avr8 board = at90usb1286 -lib_deps = ${common.lib_deps} - TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip lib_ignore = TMCStepper -src_filter = ${common.default_src_filter} + # # AT90USB1286 boards using DFU bootloader @@ -222,10 +195,7 @@ src_filter = ${common.default_src_filter} + # [env:at90usb1286_dfu] platform = teensy -board = at90usb1286 -lib_deps = ${common.lib_deps} -lib_ignore = TMCStepper -src_filter = ${common.default_src_filter} + +extends = env:at90usb1286_cdc # # Due (Atmel SAM3X8E ARM Cortex-M3) @@ -255,7 +225,7 @@ build_flags = ${common.build_flags} # # Archim SAM # -[env:DUE_archim] +[common_DUE_archim] platform = atmelsam board = due src_filter = ${common.default_src_filter} + @@ -263,54 +233,49 @@ build_flags = ${common.build_flags} -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON extra_scripts = Marlin/src/HAL/DUE/upload_extra_script.py -[env:DUE_archim_debug] +[env:DUE_archim] +platform = ${common_DUE_archim.platform} +extends = common_DUE_archim + # Used when WATCHDOG_RESET_MANUAL is enabled -platform = atmelsam -board = due -src_filter = ${common.default_src_filter} + -build_flags = ${common.build_flags} - -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON - -funwind-tables -mpoke-function-name -extra_scripts = Marlin/src/HAL/DUE/upload_extra_script.py +[env:DUE_archim_debug] +platform = ${common_DUE_archim.platform} +extends = common_DUE_archim +build_flags = ${common_DUE_archim.build_flags} -funwind-tables -mpoke-function-name + +# +# NXP LPC176x ARM Cortex-M3 +# +[common_LPC] +platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.2.zip +board = nxp_lpc1768 +build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g ${common.build_flags} +lib_ldf_mode = off +lib_compat_mode = strict +extra_scripts = Marlin/src/HAL/LPC1768/upload_extra_script.py +src_filter = ${common.default_src_filter} + +lib_deps = Servo + LiquidCrystal + U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip + TMCStepper@>=0.6.2 + Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip + SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip +# debug options for backtrace +# -funwind-tables +# -mpoke-function-name # # NXP LPC176x ARM Cortex-M3 # [env:LPC1768] -platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.2.zip -board = nxp_lpc1768 -build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g ${common.build_flags} -# debug options for backtrace -# -funwind-tables -# -mpoke-function-name -lib_ldf_mode = off -lib_compat_mode = strict -extra_scripts = Marlin/src/HAL/LPC1768/upload_extra_script.py -src_filter = ${common.default_src_filter} + -lib_deps = Servo - LiquidCrystal - U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip - TMCStepper@>=0.6.2 - Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip - SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip +platform = ${common_LPC.platform} +extends = common_LPC +board = nxp_lpc1768 [env:LPC1769] -platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.2.zip -board = nxp_lpc1769 -build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g ${common.build_flags} -# debug options for backtrace -# -funwind-tables -# -mpoke-function-name -lib_ldf_mode = off -lib_compat_mode = strict -extra_scripts = Marlin/src/HAL/LPC1768/upload_extra_script.py -src_filter = ${common.default_src_filter} + -lib_deps = Servo - LiquidCrystal - U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip - TMCStepper@>=0.6.2 - Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip - SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip +platform = ${common_LPC.platform} +extends = common_LPC +board = nxp_lpc1769 # # STM32F103RC @@ -610,9 +575,10 @@ platform = ststm32 platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = STEVAL_STM32F401VE build_flags = ${common.build_flags} - -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE - -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" - -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS + -DTARGET_STM32F4 -DSTM32F401xE -DUSBCON + -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" + -DARDUINO_STEVAL -DDISABLE_GENERIC_SERIALUSB + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -628,9 +594,9 @@ platform = ststm32 platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} board = FLYF407ZG build_flags = ${common.build_flags} - -DSTM32F4 -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" - -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x8000 - -IMarlin/src/HAL/STM32 + -DTARGET_STM32F4 -DSTM32F4 -DUSBCON + -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" + -DVECT_TAB_OFFSET=0x8000 -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = Adafruit NeoPixel, SailfishLCD, SlowSoftI2CMaster, SoftwareSerial From 9b92d5fb0e9ecf570181f4ebd5ab436a5870dd55 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 29 May 2020 00:06:03 +0000 Subject: [PATCH 0542/1454] [cron] Bump distribution date (2020-05-29) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ddc99e648b..25e0a77758 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-28" + #define STRING_DISTRIBUTION_DATE "2020-05-29" #endif /** From 30832ce9156fd21a82c494a35681ad25f35f12ae Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 30 May 2020 00:06:08 +0000 Subject: [PATCH 0543/1454] [cron] Bump distribution date (2020-05-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 25e0a77758..954dd98bf4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-29" + #define STRING_DISTRIBUTION_DATE "2020-05-30" #endif /** From 200ba87d63f97c7ceacbc839f2077e6734f994ed Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 31 May 2020 00:06:32 +0000 Subject: [PATCH 0544/1454] [cron] Bump distribution date (2020-05-31) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 954dd98bf4..c6efae7749 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-30" + #define STRING_DISTRIBUTION_DATE "2020-05-31" #endif /** From 6ee81f0d26b6c6a8fa7fa19d764c00701ffba84b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 30 May 2020 22:32:38 -0500 Subject: [PATCH 0545/1454] eeprom_init from STM32F1/access_start --- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index 5454053174..b5c658a9e1 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -39,6 +39,7 @@ size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { + eeprom_init(); #if ENABLED(SPI_EEPROM) #if SPI_CHAN_EEPROM1 == 1 SET_OUTPUT(BOARD_SPI1_SCK_PIN); From 7628895ac861460bdc6b916e32de8e6a32bb738d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 18 May 2020 13:58:11 -0500 Subject: [PATCH 0546/1454] Apply misc TERN --- Marlin/src/gcode/calibrate/G28.cpp | 7 ++----- Marlin/src/module/temperature.cpp | 6 +----- 2 files changed, 3 insertions(+), 10 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index e44d94fc55..bd847658ca 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -369,11 +369,8 @@ void GcodeSuite::G28() { if (doZ) { TERN_(BLTOUCH, bltouch.init()); - #if ENABLED(Z_SAFE_HOMING) - home_z_safely(); - #else - homeaxis(Z_AXIS); - #endif + + TERN(Z_SAFE_HOMING, home_z_safely(), homeaxis(Z_AXIS)); #if HOMING_Z_WITH_PROBE && defined(Z_AFTER_PROBING) #if Z_AFTER_HOMING > Z_AFTER_PROBING diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 264d0a9039..1fcc849241 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -900,11 +900,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #else // No PID enabled - #if HEATER_IDLE_HANDLER - const bool is_idling = hotend_idle[ee].timed_out; - #else - constexpr bool is_idling = false; - #endif + const bool is_idling = TERN0(HEATER_IDLE_HANDLER, hotend_idle[ee].timed_out); const float pid_output = (!is_idling && temp_hotend[ee].celsius < temp_hotend[ee].target) ? BANG_MAX : 0; #endif From 3430d45f533ecbd7ff0dc253060e403ac2896fae Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 30 May 2020 21:27:21 -0700 Subject: [PATCH 0547/1454] BTT SKR Mini E3 V2 (#18088) Co-authored-by: Scott Lahteine --- Marlin/src/core/boards.h | 25 ++++---- Marlin/src/pins/pins.h | 2 + .../src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h | 64 +++++++++++-------- .../pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h | 59 +++++++++++++++++ 4 files changed, 110 insertions(+), 40 deletions(-) create mode 100644 Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index aa6c7162cf..48b1a113f6 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -292,18 +292,19 @@ #define BOARD_BTT_SKR_MINI_V1_1 4013 // BigTreeTech SKR Mini v1.1 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_0 4014 // BigTreeTech SKR Mini E3 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_2 4015 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4016 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4017 // JGAurora A5S A1 (STM32F103ZET6) -#define BOARD_FYSETC_AIO_II 4018 // FYSETC AIO_II -#define BOARD_FYSETC_CHEETAH 4019 // FYSETC Cheetah -#define BOARD_FYSETC_CHEETAH_V12 4020 // FYSETC Cheetah V1.2 -#define BOARD_LONGER3D_LK 4021 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 -#define BOARD_GTM32_MINI 4022 // STM32F103VET6 controller -#define BOARD_GTM32_MINI_A30 4023 // STM32F103VET6 controller -#define BOARD_GTM32_REV_B 4024 // STM32F103VET6 controller -#define BOARD_MKS_ROBIN_E3D 4025 // MKS Robin E3D (STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3 4026 // MKS Robin E3 (STM32F103RCT6) -#define BOARD_MALYAN_M300 4027 // STM32F070-based delta +#define BOARD_BTT_SKR_MINI_E3_V2_0 4016 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 4017 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 4018 // JGAurora A5S A1 (STM32F103ZET6) +#define BOARD_FYSETC_AIO_II 4019 // FYSETC AIO_II +#define BOARD_FYSETC_CHEETAH 4020 // FYSETC Cheetah +#define BOARD_FYSETC_CHEETAH_V12 4021 // FYSETC Cheetah V1.2 +#define BOARD_LONGER3D_LK 4022 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 +#define BOARD_GTM32_MINI 4023 // STM32F103VET6 controller +#define BOARD_GTM32_MINI_A30 4024 // STM32F103VET6 controller +#define BOARD_GTM32_REV_B 4025 // STM32F103VET6 controller +#define BOARD_MKS_ROBIN_E3D 4026 // MKS Robin E3D (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3 4027 // MKS Robin E3 (STM32F103RCT6) +#define BOARD_MALYAN_M300 4028 // STM32F070-based delta // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 3dc7a67593..9f67781533 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -512,6 +512,8 @@ #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V1_2) #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB +#elif MB(BTT_SKR_MINI_E3_V2_0) + #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_E3_DIP) #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(JGAURORA_A5S_A1) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h index 4a435d6740..951d83baba 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3.h @@ -92,37 +92,55 @@ // #define HEATER_0_PIN PC8 // "HE" #define HEATER_BED_PIN PC9 // "HB" -#define FAN_PIN PA8 // "FAN0" + +#ifdef SKR_MINI_E3_V2 + #define FAN_PIN PC6 +#else + #define FAN_PIN PA8 // "FAN0" +#endif // // USB connect control // -#define USB_CONNECT_PIN PC13 +#ifdef SKR_MINI_E3_V2 + #define USB_CONNECT_PIN PA14 +#else + #define USB_CONNECT_PIN PC13 +#endif + #define USB_CONNECT_INVERTING false /** - * _____ - * 5V | 1 2 | GND - * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) - * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10| PB5 (BEEPER) - * ----- - * EXP1 + * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 + * _____ _____ + * 5V | 1 2 | GND 5V | 1 2 | GND + * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) + * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) + * RESET | 7 8 | PA9 (BTN_EN1) RESET | 7 8 | PA9 (BTN_EN1) + * (BTN_ENC) PB6 | 9 10| PB5 (BEEPER) (BTN_ENC) PA15 | 9 10| PB5 (BEEPER) + * ----- ----- + * EXP1 EXP1 */ +#ifdef SKR_MINI_E3_V2 + #define EXP1_9 PA15 + #define EXP1_3 PB15 +#else + #define EXP1_9 PB6 + #define EXP1_3 PB7 +#endif #if HAS_SPI_LCD #if ENABLED(CR10_STOCKDISPLAY) #define BEEPER_PIN PB5 + #define BTN_ENC EXP1_9 - #define BTN_ENC PB6 #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PB7 + #define LCD_PINS_ENABLE EXP1_3 #define LCD_PINS_D4 PB9 #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -130,7 +148,7 @@ #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." #define LCD_PINS_RS PB9 - #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_ENABLE EXP1_9 #define LCD_PINS_D4 PB8 #define LCD_PINS_D5 PA10 #define LCD_PINS_D6 PA9 @@ -139,25 +157,15 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - /** Creality Ender-2 display pinout - * _____ - * 5V | 1 2 | GND - * (MOSI) PB7 | 3 4 | PB8 (LCD_RS) - * (LCD_A0) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10| PB5 (SCK) - * ----- - * EXP1 - */ - - #define BTN_ENC PB6 + #define BTN_ENC EXP1_9 #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define DOGLCD_CS PB8 #define DOGLCD_A0 PB9 #define DOGLCD_SCK PB5 - #define DOGLCD_MOSI PB7 + #define DOGLCD_MOSI EXP1_3 + #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -171,7 +179,7 @@ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3.h' for details. Comment out this line to continue." - /** FYSECT TFT TFT81050 display pinout + /** FYSETC TFT TFT81050 display pinout * * Board Display * _____ _____ @@ -202,7 +210,7 @@ #define CLCD_SPI_BUS 1 // SPI1 connector - #define BEEPER_PIN PB6 + #define BEEPER_PIN EXP1_9 #define CLCD_MOD_RESET PA9 #define CLCD_SPI_CS PB8 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h new file mode 100644 index 0000000000..1d5cf0f653 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h @@ -0,0 +1,59 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define SKR_MINI_E3_V2 + +// Onboard I2C EEPROM +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #undef NO_EEPROM_SELECTED +#endif + +#include "pins_BTT_SKR_MINI_E3.h" + +#define BOARD_INFO_NAME "BIGTREE SKR Mini E3 V2.0" + +// Release PA13/PA14 (led, usb control) from SWD pins +#define DISABLE_DEBUG + +#define NEOPIXEL_PIN PA8 // LED driving pin + +#define PS_ON_PIN PC13 // Power Supply Control + +#define FAN1_PIN PC7 + +#ifndef CONTROLLER_FAN_PIN + #define CONTROLLER_FAN_PIN FAN1_PIN +#endif + +/** + * TMC220x stepper drivers + * Hardware serial communication ports. + */ +#if HAS_TMC_UART + #define X_HARDWARE_SERIAL Serial4 + #define Y_HARDWARE_SERIAL Serial4 + #define Z_HARDWARE_SERIAL Serial4 + #define E0_HARDWARE_SERIAL Serial4 +#endif From 2ad3da98d4a733791eba595c9c79fcc9d4106598 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 30 May 2020 23:28:16 -0500 Subject: [PATCH 0548/1454] Fix some spelling --- Marlin/src/pins/ramps/pins_RAMPS.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index aed2e93d0a..8f7b745e66 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -726,7 +726,7 @@ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. Comment out this line to continue." - /** FYSECT TFT TFT81050 display pinout + /** FYSETC TFT TFT81050 display pinout * * Board Display * _____ _____ diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 01dd6a7e9f..05600a9a9d 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -231,7 +231,7 @@ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. Comment out this line to continue." - /** FYSECT TFT TFT81050 display pinout + /** FYSETC TFT TFT81050 display pinout * * Board Display * _____ _____ From 801f99edadbf37966f231a8ae4b06fd93ff58cb1 Mon Sep 17 00:00:00 2001 From: "Leandro A. F. Pereira" Date: Sat, 30 May 2020 21:59:29 -0700 Subject: [PATCH 0549/1454] SDCARD_READONLY (#17884) --- Marlin/Configuration_adv.h | 2 ++ Marlin/src/inc/SanityCheck.h | 14 ++++++++++ Marlin/src/sd/Sd2Card.cpp | 21 +++++++++------ Marlin/src/sd/SdBaseFile.cpp | 40 ++++++++++++++++++++++++--- Marlin/src/sd/SdVolume.cpp | 26 +++++++++++------- Marlin/src/sd/cardreader.cpp | 42 +++++++++++++++++------------ buildroot/share/tests/LPC1768-tests | 3 +-- 7 files changed, 108 insertions(+), 40 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 22755f8122..ec6cb27ec4 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1084,6 +1084,8 @@ // Enable this option and set to HIGH if your SD cards are incorrectly detected. //#define SD_DETECT_STATE HIGH + //#define SDCARD_READONLY // Read-only SD card (to save over 2K of flash) + #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index da29c0ecf0..ab3b6b8a11 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2062,6 +2062,20 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #endif +/** + * Make sure features that need to write to the SD card are + * disabled unless write support is enabled. + */ +#if ENABLED(SDCARD_READONLY) + #if ENABLED(POWER_LOSS_RECOVERY) + #error "POWER_LOSS_RECOVERY is incompatible with SDCARD_READONLY." + #elif ENABLED(BINARY_FILE_TRANSFER) + #error "BINARY_FILE_TRANSFER is incompatible with SDCARD_READONLY." + #elif ENABLED(SDCARD_EEPROM_EMULATION) + #error "SDCARD_EEPROM_EMULATION is incompatible with SDCARD_READONLY." + #endif +#endif + /** * Make sure only one display is enabled */ diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index e21662afc1..b5a3960890 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -179,8 +179,11 @@ void Sd2Card::chipSelect() { * \return true for success, false for failure. */ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { + if (ENABLED(SDCARD_READONLY)) return false; + csd_t csd; if (!readCSD(&csd)) goto FAIL; + // check for single block erase if (!csd.v1.erase_blk_en) { // erase size mask @@ -535,9 +538,10 @@ bool Sd2Card::waitNotBusy(const millis_t timeout_ms) { * \return true for success, false for failure. */ bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { - if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card + if (ENABLED(SDCARD_READONLY)) return false; bool success = false; + if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card if (!cardCommand(CMD24, blockNumber)) { if (writeData(DATA_START_BLOCK, src)) { if (waitNotBusy(SD_WRITE_TIMEOUT)) { // Wait for flashing to complete @@ -561,6 +565,8 @@ bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { * \return true for success, false for failure. */ bool Sd2Card::writeData(const uint8_t* src) { + if (ENABLED(SDCARD_READONLY)) return false; + bool success = true; chipSelect(); // Wait for previous write to finish @@ -574,14 +580,9 @@ bool Sd2Card::writeData(const uint8_t* src) { // Send one block of data for write block or write multiple blocks bool Sd2Card::writeData(const uint8_t token, const uint8_t* src) { + if (ENABLED(SDCARD_READONLY)) return false; - const uint16_t crc = - #if ENABLED(SD_CHECK_AND_RETRY) - CRC_CCITT(src, 512) - #else - 0xFFFF - #endif - ; + const uint16_t crc = TERN(SD_CHECK_AND_RETRY, CRC_CCITT(src, 512), 0xFFFF); spiSendBlock(token, src); spiSend(crc >> 8); spiSend(crc & 0xFF); @@ -607,6 +608,8 @@ bool Sd2Card::writeData(const uint8_t token, const uint8_t* src) { * \return true for success, false for failure. */ bool Sd2Card::writeStart(uint32_t blockNumber, const uint32_t eraseCount) { + if (ENABLED(SDCARD_READONLY)) return false; + bool success = false; if (!cardAcmd(ACMD23, eraseCount)) { // Send pre-erase count if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card @@ -626,6 +629,8 @@ bool Sd2Card::writeStart(uint32_t blockNumber, const uint32_t eraseCount) { * \return true for success, false for failure. */ bool Sd2Card::writeStop() { + if (ENABLED(SDCARD_READONLY)) return false; + bool success = false; chipSelect(); if (waitNotBusy(SD_WRITE_TIMEOUT)) { diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 27c191a6a6..6e43c9f7c6 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -47,6 +47,8 @@ void (*SdBaseFile::dateTime_)(uint16_t* date, uint16_t* time) = 0; // add a cluster to a file bool SdBaseFile::addCluster() { + if (ENABLED(SDCARD_READONLY)) return false; + if (!vol_->allocContiguous(1, &curCluster_)) return false; // if first cluster of file link to directory entry @@ -60,6 +62,8 @@ bool SdBaseFile::addCluster() { // Add a cluster to a directory file and zero the cluster. // return with first block of cluster in the cache bool SdBaseFile::addDirCluster() { + if (ENABLED(SDCARD_READONLY)) return false; + uint32_t block; // max folder size if (fileSize_ / sizeof(dir_t) >= 0xFFFF) return false; @@ -153,6 +157,8 @@ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { * */ bool SdBaseFile::createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size) { + if (ENABLED(SDCARD_READONLY)) return false; + uint32_t count; // don't allow zero length file if (size == 0) return false; @@ -419,6 +425,8 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { * directory, \a path is invalid or already exists in \a parent. */ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { + if (ENABLED(SDCARD_READONLY)) return false; + uint8_t dname[11]; SdBaseFile dir1, dir2; SdBaseFile* sub = &dir1; @@ -449,6 +457,8 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { } bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { + if (ENABLED(SDCARD_READONLY)) return false; + uint32_t block; dir_t d; dir_t* p; @@ -632,7 +642,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t ofla } else { // don't create unless O_CREAT and O_WRITE - if (!(oflag & O_CREAT) || !(oflag & O_WRITE)) return false; + if ((oflag & (O_CREAT | O_WRITE)) != (O_CREAT | O_WRITE)) return false; if (emptyFound) { index = dirIndex_; p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); @@ -716,8 +726,14 @@ bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) { // open a cached directory entry. Assumes vol_ is initialized bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { + dir_t* p; + + #if ENABLED(SDCARD_READONLY) + if (oflag & (O_WRITE | O_CREAT | O_TRUNC)) goto FAIL; + #endif + // location of entry in cache - dir_t* p = &vol_->cache()->dir[dirIndex]; + p = &vol_->cache()->dir[dirIndex]; // write or truncate is an error for a directory or read-only file if (p->attributes & (DIR_ATT_READ_ONLY | DIR_ATT_DIRECTORY)) { @@ -1135,6 +1151,8 @@ dir_t* SdBaseFile::readDirCache() { * or an I/O error occurred. */ bool SdBaseFile::remove() { + if (ENABLED(SDCARD_READONLY)) return false; + dir_t* d; // free any clusters - will fail if read-only or directory if (!truncate(0)) return false; @@ -1172,6 +1190,8 @@ bool SdBaseFile::remove() { * or an I/O error occurred. */ bool SdBaseFile::remove(SdBaseFile* dirFile, const char* path) { + if (ENABLED(SDCARD_READONLY)) return false; + SdBaseFile file; return file.open(dirFile, path, O_WRITE) ? file.remove() : false; } @@ -1187,6 +1207,8 @@ bool SdBaseFile::remove(SdBaseFile* dirFile, const char* path) { * file, newPath is invalid or already exists, or an I/O error occurs. */ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) { + if (ENABLED(SDCARD_READONLY)) return false; + dir_t entry; uint32_t dirCluster = 0; SdBaseFile file; @@ -1279,6 +1301,8 @@ restore: * directory, is not empty, or an I/O error occurred. */ bool SdBaseFile::rmdir() { + if (ENABLED(SDCARD_READONLY)) return false; + // must be open subdirectory if (!isSubDir()) return false; @@ -1317,6 +1341,8 @@ bool SdBaseFile::rmdir() { * \return true for success, false for failure. */ bool SdBaseFile::rmRfStar() { + if (ENABLED(SDCARD_READONLY)) return false; + uint32_t index; SdBaseFile f; rewind(); @@ -1424,7 +1450,7 @@ void SdBaseFile::setpos(filepos_t* pos) { */ bool SdBaseFile::sync() { // only allow open files and directories - if (!isOpen()) goto FAIL; + if (ENABLED(SDCARD_READONLY) || !isOpen()) goto FAIL; if (flags_ & F_FILE_DIR_DIRTY) { dir_t* d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); @@ -1524,6 +1550,8 @@ bool SdBaseFile::timestamp(SdBaseFile* file) { */ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t minute, uint8_t second) { + if (ENABLED(SDCARD_READONLY)) return false; + uint16_t dirDate, dirTime; dir_t* d; @@ -1575,6 +1603,8 @@ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, * \a length is greater than the current file size or an I/O error occurs. */ bool SdBaseFile::truncate(uint32_t length) { + if (ENABLED(SDCARD_READONLY)) return false; + uint32_t newPos; // error if not a normal file or read-only if (!isFile() || !(flags_ & O_WRITE)) return false; @@ -1636,6 +1666,10 @@ bool SdBaseFile::truncate(uint32_t length) { * */ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { + #if ENABLED(SDCARD_READONLY) + writeError = true; return -1; + #endif + // convert void* to uint8_t* - must be before goto statements const uint8_t* src = reinterpret_cast(buf); diff --git a/Marlin/src/sd/SdVolume.cpp b/Marlin/src/sd/SdVolume.cpp index 1d4c56a344..0effc31aa5 100644 --- a/Marlin/src/sd/SdVolume.cpp +++ b/Marlin/src/sd/SdVolume.cpp @@ -46,6 +46,8 @@ // find a contiguous group of clusters bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { + if (ENABLED(SDCARD_READONLY)) return false; + // start of group uint32_t bgnCluster; // end of group @@ -117,18 +119,20 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { } bool SdVolume::cacheFlush() { - if (cacheDirty_) { - if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) - return false; - - // mirror FAT tables - if (cacheMirrorBlock_) { - if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) + #if DISABLED(SDCARD_READONLY) + if (cacheDirty_) { + if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) return false; - cacheMirrorBlock_ = 0; + + // mirror FAT tables + if (cacheMirrorBlock_) { + if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) + return false; + cacheMirrorBlock_ = 0; + } + cacheDirty_ = 0; } - cacheDirty_ = 0; - } + #endif return true; } @@ -190,6 +194,8 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { // Store a FAT entry bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { + if (ENABLED(SDCARD_READONLY)) return false; + uint32_t lba; // error if reserved cluster if (cluster < 2) return false; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 7be69beb91..9ce2c5304c 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -446,8 +446,8 @@ void CardReader::endFilePrint(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { } void CardReader::openLogFile(char * const path) { - flag.logging = true; - openFileWrite(path); + flag.logging = DISABLED(SDCARD_READONLY); + TERN(SDCARD_READONLY,,openFileWrite(path)); } // @@ -573,15 +573,19 @@ void CardReader::openFileWrite(char * const path) { const char * const fname = diveToFile(false, curDir, path); if (!fname) return; - if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { - flag.saving = true; - selectFileByName(fname); - TERN_(EMERGENCY_PARSER, emergency_parser.disable()); - echo_write_to_file(fname); - ui.set_status(fname); - } - else + #if ENABLED(SDCARD_READONLY) openFailed(fname); + #else + if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { + flag.saving = true; + selectFileByName(fname); + TERN_(EMERGENCY_PARSER, emergency_parser.disable()); + echo_write_to_file(fname); + ui.set_status(fname); + } + else + openFailed(fname); + #endif } // @@ -596,13 +600,17 @@ void CardReader::removeFile(const char * const name) { const char * const fname = diveToFile(false, curDir, name); if (!fname) return; - if (file.remove(curDir, fname)) { - SERIAL_ECHOLNPAIR("File deleted:", fname); - sdpos = 0; - TERN_(SDCARD_SORT_ALPHA, presort()); - } - else - SERIAL_ECHOLNPAIR("Deletion failed, File: ", fname, "."); + #if ENABLED(SDCARD_READONLY) + SERIAL_ECHOLNPAIR("Deletion failed (read-only), File: ", fname, "."); + #else + if (file.remove(curDir, fname)) { + SERIAL_ECHOLNPAIR("File deleted:", fname); + sdpos = 0; + TERN_(SDCARD_SORT_ALPHA, presort()); + } + else + SERIAL_ECHOLNPAIR("Deletion failed, File: ", fname, "."); + #endif } void CardReader::report_status() { diff --git a/buildroot/share/tests/LPC1768-tests b/buildroot/share/tests/LPC1768-tests index 332d22396e..2f206f02f2 100755 --- a/buildroot/share/tests/LPC1768-tests +++ b/buildroot/share/tests/LPC1768-tests @@ -15,8 +15,7 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB -opt_enable VIKI2 SDSUPPORT SERIAL_PORT_2 NEOPIXEL_LED - +opt_enable VIKI2 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 NEOPIXEL_LED opt_set NEOPIXEL_PIN P1_16 exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" From 46112b9d500f2d568ba1babe6ca25149b502f001 Mon Sep 17 00:00:00 2001 From: git-user44 <22965693+git-user44@users.noreply.github.com> Date: Sun, 31 May 2020 06:21:08 +0100 Subject: [PATCH 0550/1454] Adjust Melzi ST display timing (#18160) --- Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 50d3a53779..47c1f21416 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -180,6 +180,13 @@ // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. #define BEEPER_PIN 27 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #define BOARD_ST7920_DELAY_3 DELAY_NS(0) + #endif + #else // Sanguinololu >=1.3 #define LCD_PINS_RS 4 #define LCD_PINS_ENABLE 17 From 815c8d2b5562115932783c9b3b93372df157f30b Mon Sep 17 00:00:00 2001 From: Eyal <109809+eyal0@users.noreply.github.com> Date: Sat, 30 May 2020 23:26:15 -0600 Subject: [PATCH 0551/1454] Improve G2 / G3 motion accuracy (#18144) --- Marlin/src/gcode/motion/G2_G3.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 91923121c5..5255db23b1 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -117,8 +117,8 @@ void plan_arc( uint16_t segments = FLOOR(mm_of_travel / seg_length); if (segments < min_segments) { // Too few segments? segments = min_segments; // More segments - seg_length = mm_of_travel / segments; // but also shorter } + seg_length = mm_of_travel / segments; /** * Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, @@ -151,8 +151,9 @@ void plan_arc( const float theta_per_segment = angular_travel / segments, linear_per_segment = linear_travel / segments, extruder_per_segment = extruder_travel / segments, - sin_T = theta_per_segment, - cos_T = 1 - 0.5f * sq(theta_per_segment); // Small angle approximation + sq_theta_per_segment = sq(theta_per_segment), + sin_T = theta_per_segment - sq_theta_per_segment*theta_per_segment/6, + cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation // Initialize the linear axis raw[l_axis] = current_position[l_axis]; @@ -218,7 +219,7 @@ void plan_arc( planner.apply_leveling(raw); #endif - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, seg_length + if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif From d2d52e3c348c8b2f135d59fe2eecafc22ab15db3 Mon Sep 17 00:00:00 2001 From: MoellerDi Date: Sun, 31 May 2020 07:43:37 +0200 Subject: [PATCH 0552/1454] Declare MSerial6 (etc.) for STM32 (#18149) --- Marlin/src/HAL/STM32/MarlinSerial.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h index 290fdce9ee..d971ff704b 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.h +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -52,3 +52,9 @@ extern MarlinSerial MSerial2; extern MarlinSerial MSerial3; extern MarlinSerial MSerial4; extern MarlinSerial MSerial5; +extern MarlinSerial MSerial6; +extern MarlinSerial MSerial7; +extern MarlinSerial MSerial8; +extern MarlinSerial MSerial9; +extern MarlinSerial MSerial10; +extern MarlinSerial MSerialLP1; From dcb90a8d61849e8ccbd5dc83fa88b56db1d7df33 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 30 May 2020 22:45:04 -0700 Subject: [PATCH 0553/1454] No SERIAL_STATS for LPC, STM32 (#18145) --- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 8 ++++++++ Marlin/src/HAL/STM32/inc/SanityCheck.h | 8 ++++++++ Marlin/src/HAL/STM32F1/inc/SanityCheck.h | 8 ++++++++ 3 files changed, 24 insertions(+) diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 2606ef26b5..f4fff5a417 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -251,3 +251,11 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #undef USEDI2CDEV_M #endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." +#endif + +#if ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." +#endif diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 7236b7f4ed..98dc319817 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -48,3 +48,11 @@ #if !defined(STM32F4xx) && ENABLED(FLASH_EEPROM_LEVELING) #error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4 hardware." #endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." +#endif + +#if ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." +#endif diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index 33365fab4b..112f03e8d8 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -49,3 +49,11 @@ #endif #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." #endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." +#endif + +#if ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." +#endif From 657eeab0138953d59264cc06c872c452d5a62858 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 31 May 2020 01:40:16 -0500 Subject: [PATCH 0554/1454] Improve some probe sanity errors --- Marlin/src/inc/SanityCheck.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ab3b6b8a11..905bcc0bd7 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -295,13 +295,13 @@ #elif defined(UBL_PROBE_PT_1_X) || defined(UBL_PROBE_PT_1_Y) || defined(UBL_PROBE_PT_2_X) || defined(UBL_PROBE_PT_2_Y) || defined(UBL_PROBE_PT_3_X) || defined(UBL_PROBE_PT_3_Y) #error "UBL_PROBE_PT_[123]_[XY] is no longer required. Please remove it from Configuration.h." #elif defined(LEFT_PROBE_BED_POSITION) - #error "LEFT_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_LEFT. Please update your configuration." + #error "LEFT_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_LEFT instead." #elif defined(RIGHT_PROBE_BED_POSITION) - #error "RIGHT_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_RIGHT. Please update your configuration." + #error "RIGHT_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_RIGHT instead." #elif defined(FRONT_PROBE_BED_POSITION) - #error "FRONT_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_FRONT. Please update your configuration." + #error "FRONT_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_FRONT instead." #elif defined(BACK_PROBE_BED_POSITION) - #error "BACK_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_BACK. Please update your configuration." + #error "BACK_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_BACK instead." #elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY) #error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY. Please update your configuration." #elif defined(BABYSTEP_ZPROBE_GFX_REVERSE) From 6515100807762a2ed430aabfd6d20b011ee3d2f8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 1 Jun 2020 00:06:36 +0000 Subject: [PATCH 0555/1454] [cron] Bump distribution date (2020-06-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c6efae7749..6459baf515 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-31" + #define STRING_DISTRIBUTION_DATE "2020-06-01" #endif /** From e380498512a325fe1e70b20d4c60a81f606eddbf Mon Sep 17 00:00:00 2001 From: Jonathan Gilbert Date: Mon, 1 Jun 2020 00:19:36 -0500 Subject: [PATCH 0556/1454] Fix Z homing with custom probe pins (#18150) --- Marlin/src/module/motion.cpp | 25 +++++++------------------ 1 file changed, 7 insertions(+), 18 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 673eee3a92..09f0f390c5 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1534,24 +1534,13 @@ void homeaxis(const AxisEnum axis) { // Only Z homing (with probe) is permitted if (axis != Z_AXIS) { BUZZ(100, 880); return; } #else - #define _CAN_HOME(A) \ - (axis == _AXIS(A) && ((A##_MIN_PIN > -1 && A##_HOME_DIR < 0) || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0))) - #if X_SPI_SENSORLESS - #define CAN_HOME_X true - #else - #define CAN_HOME_X _CAN_HOME(X) - #endif - #if Y_SPI_SENSORLESS - #define CAN_HOME_Y true - #else - #define CAN_HOME_Y _CAN_HOME(Y) - #endif - #if Z_SPI_SENSORLESS - #define CAN_HOME_Z true - #else - #define CAN_HOME_Z _CAN_HOME(Z) - #endif - if (!CAN_HOME_X && !CAN_HOME_Y && !CAN_HOME_Z) return; + #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ + ENABLED(A##_SPI_SENSORLESS) \ + || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \ + || (A##_MIN_PIN > 0 && A##_HOME_DIR < 0) \ + || (A##_MAX_PIN > 0 && A##_HOME_DIR > 0) \ + )) + if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; #endif if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", axis_codes[axis], ")"); From bda380513addbb6d69b1aaf287876225193f240e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 1 Jun 2020 17:02:49 -0500 Subject: [PATCH 0557/1454] Add valid() to recovery.info --- Marlin/src/feature/powerloss.h | 4 +++- Marlin/src/gcode/feature/powerloss/M1000.cpp | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index ff3fef80fa..affa2cae44 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -106,6 +106,8 @@ typedef struct { uint8_t valid_foot; + bool valid() { return valid_head && valid_head == valid_foot; } + } job_recovery_info_t; class PrintJobRecovery { @@ -164,7 +166,7 @@ class PrintJobRecovery { } #endif - static inline bool valid() { return info.valid_head && info.valid_head == info.valid_foot; } + static inline bool valid() { return info.valid(); } #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) static void debug(PGM_P const prefix); diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index dbcd819d70..c53e8fbccc 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -41,7 +41,7 @@ inline void plr_error(PGM_P const prefix) { #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) DEBUG_ECHO_START(); serialprintPGM(prefix); - DEBUG_ECHOLNPGM(" Power-Loss Recovery Data"); + DEBUG_ECHOLNPGM(" Job Recovery Data"); #else UNUSED(prefix); #endif From 785f442c8c937b49d9d90bfef8b1e98314ccd524 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 31 May 2020 02:13:53 -0500 Subject: [PATCH 0558/1454] Group some sanity checks --- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 6 ++---- Marlin/src/HAL/STM32/inc/SanityCheck.h | 6 ++---- Marlin/src/HAL/STM32F1/inc/SanityCheck.h | 6 ++---- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 2 +- 4 files changed, 7 insertions(+), 13 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index f4fff5a417..13f2567de1 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -254,8 +254,6 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." -#endif - -#if ENABLED(SERIAL_STATS_DROPPED_RX) +#elif ENABLED(SERIAL_STATS_DROPPED_RX) #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." -#endif +#endif diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 98dc319817..4d563d506b 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -51,8 +51,6 @@ #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." -#endif - -#if ENABLED(SERIAL_STATS_DROPPED_RX) +#elif ENABLED(SERIAL_STATS_DROPPED_RX) #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." -#endif +#endif diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index 112f03e8d8..0e6e273d6c 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -52,8 +52,6 @@ #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." -#endif - -#if ENABLED(SERIAL_STATS_DROPPED_RX) +#elif ENABLED(SERIAL_STATS_DROPPED_RX) #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." -#endif +#endif diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 4ae0bf4ac0..d2517c3db7 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -1520,7 +1520,7 @@ #endif #ifndef STATUS_HOTEND8_TEXT_X #define STATUS_HOTEND8_TEXT_X STATUS_HOTEND7_TEXT_X + STATUS_HEATERS_XSPACE - #endif + #endif constexpr uint8_t status_hotend_text_x[] = ARRAY_N(HOTENDS, STATUS_HOTEND1_TEXT_X, STATUS_HOTEND2_TEXT_X, STATUS_HOTEND3_TEXT_X, STATUS_HOTEND4_TEXT_X, STATUS_HOTEND5_TEXT_X, STATUS_HOTEND6_TEXT_X, STATUS_HOTEND7_TEXT_X, STATUS_HOTEND8_TEXT_X); #define STATUS_HOTEND_TEXT_X(N) status_hotend_text_x[N] #else From 48d9a5367b6b52f16ed8a38c71905a33a5c8473b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 1 Jun 2020 17:06:27 -0500 Subject: [PATCH 0559/1454] Chirp followup --- Marlin/src/inc/Conditionals_post.h | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 3a8bee4087..57295f84b9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1880,15 +1880,6 @@ #if PIN_EXISTS(PHOTOGRAPH) #define HAS_PHOTOGRAPH 1 #endif -#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) - #define HAS_BUZZER 1 - #if LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ - #define HAS_CHIRP 1 - #endif -#endif -#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) - #define USE_BEEPER 1 -#endif #if PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE) #define HAS_CASE_LIGHT 1 #endif @@ -2377,6 +2368,16 @@ #endif #endif +#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #define HAS_BUZZER 1 + #if LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ + #define HAS_CHIRP 1 + #endif +#endif +#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #define USE_BEEPER 1 +#endif + /** * Make sure DOGLCD_SCK and DOGLCD_MOSI are defined. */ From 2bf63e29c627ec6396cd2ac84e76c2cd45d03780 Mon Sep 17 00:00:00 2001 From: cccc Date: Tue, 2 Jun 2020 07:25:13 +0800 Subject: [PATCH 0560/1454] Support for MEEB 3DP board (#18138) --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 + .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 173 ++++++++++++++ .../share/PlatformIO/boards/MEEB_3DP.json | 53 +++++ .../ldscripts/STM32F103RC_MEEB_3DP.ld | 14 ++ .../scripts/STM32F103RC_MEEB_3DP.py | 61 +++++ .../STM32F103RC_MEEB_3DP_create_variant.py | 34 +++ .../PlatformIO/variants/MEEB_3DP/board.cpp | 162 +++++++++++++ .../variants/MEEB_3DP/board/board.h | 125 ++++++++++ .../variants/MEEB_3DP/ld/bootloader.ld | 18 ++ .../variants/MEEB_3DP/ld/common.inc | 220 +++++++++++++++++ .../variants/MEEB_3DP/ld/extra_libs.inc | 7 + .../PlatformIO/variants/MEEB_3DP/ld/flash.ld | 26 ++ .../PlatformIO/variants/MEEB_3DP/ld/jtag.ld | 31 +++ .../variants/MEEB_3DP/ld/mem-flash.inc | 5 + .../variants/MEEB_3DP/ld/mem-jtag.inc | 5 + .../variants/MEEB_3DP/ld/mem-ram.inc | 5 + .../PlatformIO/variants/MEEB_3DP/ld/ram.ld | 25 ++ .../variants/MEEB_3DP/ld/stm32f103rb.ld | 18 ++ .../MEEB_3DP/ld/stm32f103rb_bootloader.ld | 17 ++ .../variants/MEEB_3DP/ld/stm32f103rc.ld | 18 ++ .../MEEB_3DP/ld/stm32f103rc_bootloader.ld | 18 ++ .../variants/MEEB_3DP/ld/stm32f103re.ld | 18 ++ .../variants/MEEB_3DP/ld/vector_symbols.inc | 78 ++++++ .../variants/MEEB_3DP/pins_arduino.h | 2 + .../PlatformIO/variants/MEEB_3DP/variant.h | 20 ++ .../variants/MEEB_3DP/wirish/boards.cpp | 225 ++++++++++++++++++ .../variants/MEEB_3DP/wirish/boards_setup.cpp | 106 +++++++++ .../variants/MEEB_3DP/wirish/start.S | 57 +++++ .../variants/MEEB_3DP/wirish/start_c.c | 95 ++++++++ .../variants/MEEB_3DP/wirish/syscalls.c | 176 ++++++++++++++ .../share/tests/STM32F103RC_cc_meeb_3dp-tests | 23 ++ platformio.ini | 35 ++- 33 files changed, 1864 insertions(+), 9 deletions(-) create mode 100644 Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h create mode 100644 buildroot/share/PlatformIO/boards/MEEB_3DP.json create mode 100644 buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld create mode 100644 buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py create mode 100644 buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/board/board.h create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/bootloader.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/common.inc create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/extra_libs.inc create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/flash.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/jtag.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-flash.inc create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-jtag.inc create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-ram.inc create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/ram.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb_bootloader.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc_bootloader.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/ld/vector_symbols.inc create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/pins_arduino.h create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/variant.h create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start.S create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start_c.c create mode 100644 buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/syscalls.c create mode 100644 buildroot/share/tests/STM32F103RC_cc_meeb_3dp-tests diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 48b1a113f6..644eeee54d 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -305,6 +305,7 @@ #define BOARD_MKS_ROBIN_E3D 4026 // MKS Robin E3D (STM32F103RCT6) #define BOARD_MKS_ROBIN_E3 4027 // MKS Robin E3 (STM32F103RCT6) #define BOARD_MALYAN_M300 4028 // STM32F070-based delta +#define BOARD_CCROBOT_MEEB_3DP 4029 // ccrobot-online.com MEEB_3DP (STM32F103RC) // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 9f67781533..b8f01e5626 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -534,6 +534,8 @@ #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3) #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 +#elif MB(CCROBOT_MEEB_3DP) + #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_cc_meeb_3dp // // ARM Cortex-M4F diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h new file mode 100644 index 0000000000..6cfa4e2144 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -0,0 +1,173 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifndef TARGET_STM32F1 + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "CCROBOT-ONLINE MEEB_3DP only supports 1 hotend / E-stepper. Comment out this line to continue." +#endif + +// https://github.com/ccrobot-online/MEEB_3DP +// Pin assignments for 32-bit MEEB_3DP +#define BOARD_INFO_NAME "CCROBOT-ONLINE MEEB_3DP" +#define DEFAULT_MACHINE_NAME "STM32F103RCT6" +#define BOARD_WEBSITE_URL "ccrobot-online.com" + +// +// Release PB4 from JTAG NRST role +// +#define DISABLE_JTAG + +// +// EEPROM +// +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE 0x800U // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Servos +// +#define SERVO0_PIN PA1 + +// +// Limit Switches +// +#define X_STOP_PIN PC0 +#define Y_STOP_PIN PC1 +#define Z_STOP_PIN PC2 + +// +// Z Probe must be this pin +// +#define Z_MIN_PROBE_PIN PC15 // "PROBE" + +// +// TMC2208 stepper drivers +// +#define X_ENABLE_PIN PB4 +#define X_STEP_PIN PC12 +#define X_DIR_PIN PC11 + +#define Y_ENABLE_PIN PC10 +#define Y_STEP_PIN PB14 +#define Y_DIR_PIN PB13 + +#define Z_ENABLE_PIN PB12 +#define Z_STEP_PIN PB2 +#define Z_DIR_PIN PB1 + +#define E0_ENABLE_PIN PB0 +#define E0_STEP_PIN PA6 +#define E0_DIR_PIN PA5 + +// Stepper drivers Serial UART +#define X_SERIAL_TX_PIN PB3 +#define X_SERIAL_RX_PIN PD2 +#define Y_SERIAL_TX_PIN PA15 +#define Y_SERIAL_RX_PIN PC6 +#define Z_SERIAL_TX_PIN PB11 +#define Z_SERIAL_RX_PIN PB10 +#define E0_SERIAL_TX_PIN PC5 +#define E0_SERIAL_RX_PIN PC4 + +// Reduce baud rate to improve software serial reliability +#define TMC_BAUD_RATE 19200 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA0 // TH0 +#define TEMP_BED_PIN PC3 // THB + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC8 // HEATER0 +#define HEATER_BED_PIN PC9 // HOT BED + +#define FAN_PIN PA7 // FAN (fan2 on board) model cool fan +#define FAN1_PIN PA8 // FAN (fan0 on board) e0 cool fan +#define FAN2_PIN PB9 // FAN (fan1 on board) controller cool fan + +// One neopixel onboard and a connector for other neopixels +#define NEOPIXEL_PIN PC7 // The NEOPIXEL LED driving pin + +/** + * 1 _____ 2 + * PB5 | · · | PB6 + * PA2 | · · | RESET + * PA3 | · · | PB8 + * PB7 | · · | PA4 + * GND | · · | VCC5 + * 9 ----- 10 + * LCD EXP + */ + +// +// LCD / Controller +// +#if ENABLED(CR10_STOCKDISPLAY) + #define BEEPER_PIN PB5 + #define BTN_EN1 PA2 + #define BTN_EN2 PA3 + #define BTN_ENC PB6 + + #define LCD_PINS_RS PB7 // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 PB8 // SCLK + #define LCD_PINS_ENABLE PA4 // DATA MOSI +#endif + +// Alter timing for graphical display +#if HAS_GRAPHICAL_LCD + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + +// +// Camera +// +#define CHDK_PIN PB15 + +#if 0 + +// +// SD-NAND +// +#if SD_CONNECTION_IS(ONBOARD) + #define ENABLE_SPI1 + #define SD_DETECT_PIN -1 + #define SCK_PIN PA5 + #define MISO_PIN PA6 + #define MOSI_PIN PA7 + #define SS_PIN PA4 +#endif + +#define ON_BOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SD_CS_PIN PA4 // Chip select for SD-NAND + +#endif diff --git a/buildroot/share/PlatformIO/boards/MEEB_3DP.json b/buildroot/share/PlatformIO/boards/MEEB_3DP.json new file mode 100644 index 0000000000..870648b325 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/MEEB_3DP.json @@ -0,0 +1,53 @@ +{ + "build": { + "core": "maple", + "cpu": "cortex-m3", + "extra_flags": "-DSTM32F103xE -DSTM32F1", + "f_cpu": "72000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x1EAF", + "0x0004" + ] + ], + "libopencm3": { + "ldscript": "stm32f103xc.ld" + }, + "mcu": "stm32f103rct6", + "variant": "MEEB_3DP" + }, + "debug": { + "jlink_device": "STM32F103RC", + "openocd_target": "stm32f1x", + "svd_path": "STM32F103xx.svd" + }, + "frameworks": [ + "arduino", + "cmsis", + "libopencm3", + "stm32cube" + ], + "name": "3D Printer control board for MEEB with 512k flash/rs422 bus/tmc2208 drivers", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 49152, + "maximum_size": 524288, + "protocol": "dfu", + "protocols": [ + "jlink", + "stlink", + "blackmagic", + "serial", + "dfu" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://github.com/ccrobot-online/MEEB_3DP", + "vendor": "CCROBOT-ONLINE" +} diff --git a/buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld new file mode 100644 index 0000000000..01609b9b2c --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08002000, LENGTH = 512K - 8K - 4K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py new file mode 100644 index 0000000000..9176ab3278 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py @@ -0,0 +1,61 @@ +try: + import configparser +except ImportError: + import ConfigParser as configparser + +import os +Import("env", "projenv") +# access to global build environment +print(env) +# access to project build environment (is used source files in "src" folder) +print(projenv) + +config = configparser.ConfigParser() +config.read("platformio.ini") + +#com_port = config.get("env:STM32F103RC_cc_meeb_3dp", "upload_port") +#print('Use the {0:s} to reboot the board to dfu mode.'.format(com_port)) + +# +# Upload actions +# + +def before_upload(source, target, env): + print("before_upload") + # do some actions + # use com_port + # + env.Execute("pwd") + +def after_upload(source, target, env): + print("after_upload") + # do some actions + # + # + env.Execute("pwd") + +print("Current build targets", map(str, BUILD_TARGETS)) + +env.AddPreAction("upload", before_upload) +env.AddPostAction("upload", after_upload) + +flash_size = 0 +vect_tab_addr = 0 + +for define in env['CPPDEFINES']: + if define[0] == "VECT_TAB_ADDR": + vect_tab_addr = define[1] + if define[0] == "STM32_FLASH_SIZE": + flash_size = define[1] + +print('Use the {0:s} address as the marlin app entry point.'.format(vect_tab_addr)) +print('Use the {0:d}KB flash version of stm32f103rct6 chip.'.format(flash_size)) + +custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld") +for i, flag in enumerate(env["LINKFLAGS"]): + if "-Wl,-T" in flag: + env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script + elif flag == "-T": + env["LINKFLAGS"][i + 1] = custom_ld_script + + diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py new file mode 100644 index 0000000000..e4f9b672d1 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py @@ -0,0 +1,34 @@ +import os,shutil +from SCons.Script import DefaultEnvironment +from platformio import util + +def copytree(src, dst, symlinks=False, ignore=None): + for item in os.listdir(src): + s = os.path.join(src, item) + d = os.path.join(dst, item) + if os.path.isdir(s): + shutil.copytree(s, d, symlinks, ignore) + else: + shutil.copy2(s, d) + +env = DefaultEnvironment() +platform = env.PioPlatform() +board = env.BoardConfig() + +FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32-maple") +assert os.path.isdir(FRAMEWORK_DIR) +assert os.path.isdir("buildroot/share/PlatformIO/variants") + +variant = board.get("build.variant") +variant_dir = os.path.join(FRAMEWORK_DIR, "STM32F1", "variants", variant) + +source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) +assert os.path.isdir(source_dir) + +if os.path.isdir(variant_dir): + shutil.rmtree(variant_dir) + +if not os.path.isdir(variant_dir): + os.mkdir(variant_dir) + +copytree(source_dir, variant_dir) \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp b/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp new file mode 100644 index 0000000000..5b602de49a --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp @@ -0,0 +1,162 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish/boards/maple/board.cpp + * @author Marti Bolivar + * @brief Maple board file. + */ + +#include // For this board's header file + + +/* Roger Clark. Added next to includes for changes to Serial */ +#include +#include + +#include // For stm32_pin_info and its contents + // (these go into PIN_MAP). + +#include "boards_private.h" // For PMAP_ROW(), which makes + // PIN_MAP easier to read. + +// boardInit(): nothing special to do for Maple. +// +// When defining your own board.cpp, you can put extra code in this +// function if you have anything you want done on reset, before main() +// or setup() are called. +// +// If there's nothing special you need done, feel free to leave this +// function out, as we do here. + +void boardInit(void) { + // afio_remap(AFIO_REMAP_I2C1); +} + + +// Pin map: this lets the basic I/O functions (digitalWrite(), +// analogRead(), pwmWrite()) translate from pin numbers to STM32 +// peripherals. +// +// PMAP_ROW() lets us specify a row (really a struct stm32_pin_info) +// in the pin map. Its arguments are: +// +// - GPIO device for the pin (&gpioa, etc.) +// - GPIO bit for the pin (0 through 15) +// - Timer device, or NULL if none +// - Timer channel (1 to 4, for PWM), or 0 if none +// - ADC device, or NULL if none +// - ADC channel, or ADCx if none + +extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { +/* + gpio_dev *gpio_device; GPIO device + timer_dev *timer_device; Pin's timer device, if any. + const adc_dev *adc_device; ADC device, if any. + uint8 gpio_bit; Pin's GPIO port bit. + uint8 timer_channel; Timer channel, or 0 if none. + uint8 adc_channel; Pin ADC channel, or ADCx if none. +*/ + + {&gpioa, &timer2, &adc1, 0, 1, 0}, /* PA0 */ + {&gpioa, &timer2, &adc1, 1, 2, 1}, /* PA1 */ + {&gpioa, &timer2, &adc1, 2, 3, 2}, /* PA2 */ + {&gpioa, &timer2, &adc1, 3, 4, 3}, /* PA3 */ + {&gpioa, NULL, &adc1, 4, 0, 4}, /* PA4 */ + {&gpioa, NULL, &adc1, 5, 0, 5}, /* PA5 */ + {&gpioa, &timer3, &adc1, 6, 1, 6}, /* PA6 */ + {&gpioa, &timer3, &adc1, 7, 2, 7}, /* PA7 */ + {&gpioa, &timer1, NULL, 8, 1, ADCx}, /* PA8 */ + {&gpioa, &timer1, NULL, 9, 2, ADCx}, /* PA9 */ + {&gpioa, &timer1, NULL, 10, 3, ADCx}, /* PA10 */ + {&gpioa, NULL, NULL, 11, 0, ADCx}, /* PA11 */ + {&gpioa, NULL, NULL, 12, 0, ADCx}, /* PA12 */ + {&gpioa, NULL, NULL, 13, 0, ADCx}, /* PA13 */ + {&gpioa, NULL, NULL, 14, 0, ADCx}, /* PA14 */ + {&gpioa, NULL, NULL, 15, 0, ADCx}, /* PA15 */ + + {&gpiob, &timer3, &adc1, 0, 3, 8}, /* PB0 */ + {&gpiob, &timer3, &adc1, 1, 4, 9}, /* PB1 */ + {&gpiob, NULL, NULL, 2, 0, ADCx}, /* PB2 */ + {&gpiob, NULL, NULL, 3, 0, ADCx}, /* PB3 */ + {&gpiob, NULL, NULL, 4, 0, ADCx}, /* PB4 */ + {&gpiob, NULL, NULL, 5, 0, ADCx}, /* PB5 */ + {&gpiob, &timer4, NULL, 6, 1, ADCx}, /* PB6 */ + {&gpiob, &timer4, NULL, 7, 2, ADCx}, /* PB7 */ + {&gpiob, &timer4, NULL, 8, 3, ADCx}, /* PB8 */ + {&gpiob, NULL, NULL, 9, 0, ADCx}, /* PB9 */ + {&gpiob, NULL, NULL, 10, 0, ADCx}, /* PB10 */ + {&gpiob, NULL, NULL, 11, 0, ADCx}, /* PB11 */ + {&gpiob, NULL, NULL, 12, 0, ADCx}, /* PB12 */ + {&gpiob, NULL, NULL, 13, 0, ADCx}, /* PB13 */ + {&gpiob, NULL, NULL, 14, 0, ADCx}, /* PB14 */ + {&gpiob, NULL, NULL, 15, 0, ADCx}, /* PB15 */ + + + {&gpioc, NULL, &adc1, 0, 0, 10}, /* PC0 */ + {&gpioc, NULL, &adc1, 1, 0, 11}, /* PC1 */ + {&gpioc, NULL, &adc1, 2, 0, 12}, /* PC2 */ + {&gpioc, NULL, &adc1, 3, 0, 13}, /* PC3 */ + {&gpioc, NULL, &adc1, 4, 0, 14}, /* PC4 */ + {&gpioc, NULL, &adc1, 5, 0, 15}, /* PC5 */ + {&gpioc, &timer8, NULL, 6, 1, ADCx}, /* PC6 */ + {&gpioc, &timer8, NULL, 7, 2, ADCx}, /* PC7 */ + {&gpioc, &timer8, NULL, 8, 3, ADCx}, /* PC8 */ + {&gpioc, &timer8, NULL, 9, 4, ADCx}, /* PC9 */ + {&gpioc, NULL, NULL, 10, 0, ADCx}, /* PC10 UART4_TX/SDIO_D2 */ + {&gpioc, NULL, NULL, 11, 0, ADCx}, /* PC11 UART4_RX/SDIO_D3 */ + {&gpioc, NULL, NULL, 12, 0, ADCx}, /* PC12 UART5_TX/SDIO_CK */ + {&gpioc, NULL, NULL, 13, 0, ADCx}, /* PC13 TAMPER-RTC */ + {&gpioc, NULL, NULL, 14, 0, ADCx}, /* PC14 OSC32_IN */ + {&gpioc, NULL, NULL, 15, 0, ADCx}, /* PC15 OSC32_OUT */ + + {&gpiod, NULL, NULL, 0, 0, ADCx} , /* PD0 OSC_IN */ + {&gpiod, NULL, NULL, 1, 0, ADCx} , /* PD1 OSC_OUT */ + {&gpiod, NULL, NULL, 2, 0, ADCx} , /* PD2 TIM3_ETR/UART5_RX SDIO_CMD */ +}; + +/* Basically everything that is defined as having a timer us PWM */ +extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { + PA0,PA1,PA2,PA3,PA6,PA7,PA8,PA9,PA10,PB0,PB1,PB6,PB7,PB8,PB9,PC6,PC7,PC8,PC9 +}; + +/* Basically everything that is defined having ADC */ +extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { + PA0,PA1,PA2,PA3,PA4,PA5,PA6,PA7,PB0,PB1,PC0,PC1,PC2,PC3,PC4,PC5 +}; + +/* not sure what this us used for */ +extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { + BOARD_JTMS_SWDIO_PIN, + BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN +}; + +DEFINE_HWSERIAL(Serial1, 1); +DEFINE_HWSERIAL(Serial2, 2); +DEFINE_HWSERIAL(Serial3, 3); +DEFINE_HWSERIAL_UART(Serial4, 4); +DEFINE_HWSERIAL_UART(Serial5, 5); + diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/board/board.h b/buildroot/share/PlatformIO/variants/MEEB_3DP/board/board.h new file mode 100644 index 0000000000..da9ffd893f --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/board/board.h @@ -0,0 +1,125 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_RET6.h + * @author Marti Bolivar + * @brief Private include file for Maple RET6 Edition in boards.h + * + * See maple.h for more information on these definitions. + */ + +#ifndef _BOARDS_GENERIC_STM32F103R_H_ +#define _BOARDS_GENERIC_STM32F103R_H_ + +/* A few of these values will seem strange given that it's a + * high-density board. */ + +#define CYCLES_PER_MICROSECOND 72 +#define SYSTICK_RELOAD_VAL (F_CPU/1000) - 1 /* takes a cycle to reload */ + +// USARTS +#define BOARD_NR_USARTS 5 +#define BOARD_USART1_TX_PIN PA9 +#define BOARD_USART1_RX_PIN PA10 + +#define BOARD_USART2_TX_PIN PA2 +#define BOARD_USART2_RX_PIN PA3 + +#define BOARD_USART3_TX_PIN PB10 +#define BOARD_USART3_RX_PIN PB11 + +#define BOARD_USART4_TX_PIN PC10 +#define BOARD_USART4_RX_PIN PC11 + +#define BOARD_USART5_TX_PIN PC12 +#define BOARD_USART5_RX_PIN PD2 + +/* Note: + * + * SPI3 is unusable due to pin 43 (PB4) and NRST tie-together :(, but + * leave the definitions so as not to clutter things up. This is only + * OK since RET6 Ed. is specifically advertised as a beta board. */ +#define BOARD_NR_SPI 3 +#define BOARD_SPI1_NSS_PIN PA4 +#define BOARD_SPI1_SCK_PIN PA5 +#define BOARD_SPI1_MISO_PIN PA6 +#define BOARD_SPI1_MOSI_PIN PA7 + + + +#define BOARD_SPI2_NSS_PIN PB12 +#define BOARD_SPI2_SCK_PIN PB13 +#define BOARD_SPI2_MISO_PIN PB14 +#define BOARD_SPI2_MOSI_PIN PB15 + + +#define BOARD_SPI3_NSS_PIN PA15 +#define BOARD_SPI3_SCK_PIN PB3 +#define BOARD_SPI3_MISO_PIN PB4 +#define BOARD_SPI3_MOSI_PIN PB5 + + +/* GPIO A to E = 5 * 16 - BOOT1 not used = 79*/ +#define BOARD_NR_GPIO_PINS 51 +/* Note: NOT 19. The missing one is D38 a.k.a. BOARD_BUTTON_PIN, which + * isn't broken out to a header and is thus unusable for PWM. */ +#define BOARD_NR_PWM_PINS 19 +#define BOARD_NR_ADC_PINS 16 +#define BOARD_NR_USED_PINS 7 + +#define BOARD_JTMS_SWDIO_PIN 39 +#define BOARD_JTCK_SWCLK_PIN 40 +#define BOARD_JTDI_PIN 41 +#define BOARD_JTDO_PIN 42 +#define BOARD_NJTRST_PIN 43 + +/* USB configuration. BOARD_USB_DISC_DEV is the GPIO port containing + * the USB_DISC pin, and BOARD_USB_DISC_BIT is that pin's bit. */ +#define BOARD_USB_DISC_DEV GPIOC +#define BOARD_USB_DISC_BIT 12 + +/* + * SDIO Pins + */ +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 + +/* Pin aliases: these give the GPIO port/bit for each pin as an + * enum. These are optional, but recommended. They make it easier to + * write code using low-level GPIO functionality. */ +enum { +PA0,PA1,PA2,PA3,PA4,PA5,PA6,PA7,PA8,PA9,PA10,PA11,PA12,PA13,PA14,PA15, +PB0,PB1,PB2,PB3,PB4,PB5,PB6,PB7,PB8,PB9,PB10,PB11,PB12,PB13,PB14,PB15, +PC0,PC1,PC2,PC3,PC4,PC5,PC6,PC7,PC8,PC9,PC10,PC11,PC12,PC13,PC14,PC15, +PD0,PD1,PD2 +};/* Note PB2 is skipped as this is Boot1 and is not going to be much use as its likely to be pulled permanently low */ + +#endif diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/bootloader.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/bootloader.ld new file mode 100644 index 0000000000..ca56532fdd --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/bootloader.ld @@ -0,0 +1,18 @@ +/* + * Linker script for Generic STM32F103RE boards, using the generic bootloader (which takes the lower 8k of memory) + */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + rom (rx) : ORIGIN = 0x08002000, LENGTH = 504K +} + + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/common.inc b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/common.inc new file mode 100644 index 0000000000..e086a58bca --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/common.inc @@ -0,0 +1,220 @@ +/* + * Linker script for libmaple. + * + * Original author "lanchon" from ST forums, with modifications by LeafLabs. + */ + +OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm") + +/* + * Configure other libraries we want in the link. + * + * libgcc, libc, and libm are common across supported toolchains. + * However, some toolchains require additional archives which aren't + * present everywhere (e.g. ARM's gcc-arm-embedded releases). + * + * To hack around this, we let the build system specify additional + * archives by putting the right extra_libs.inc (in a directory under + * toolchains/) in our search path. + */ +GROUP(libgcc.a libc.a libm.a) +INCLUDE extra_libs.inc + +/* + * These force the linker to search for vector table symbols. + * + * These symbols vary by STM32 family (and also within families). + * It's up to the build system to configure the link's search path + * properly for the target MCU. + */ +INCLUDE vector_symbols.inc + +/* STM32 vector table. */ +EXTERN(__stm32_vector_table) + +/* C runtime initialization function. */ +EXTERN(start_c) + +/* main entry point */ +EXTERN(main) + +/* Initial stack pointer value. */ +EXTERN(__msp_init) +PROVIDE(__msp_init = ORIGIN(ram) + LENGTH(ram)); + +/* Reset vector and chip reset entry point */ +EXTERN(__start__) +ENTRY(__start__) +PROVIDE(__exc_reset = __start__); + +/* Heap boundaries, for libmaple */ +EXTERN(_lm_heap_start); +EXTERN(_lm_heap_end); + +SECTIONS +{ + .text : + { + __text_start__ = .; + /* + * STM32 vector table. Leave this here. Yes, really. + */ + *(.stm32.interrupt_vector) + + /* + * Program code and vague linking + */ + *(.text .text.* .gnu.linkonce.t.*) + *(.plt) + *(.gnu.warning) + *(.glue_7t) *(.glue_7) *(.vfp11_veneer) + + *(.ARM.extab* .gnu.linkonce.armextab.*) + *(.gcc_except_table) + *(.eh_frame_hdr) + *(.eh_frame) + + . = ALIGN(4); + KEEP(*(.init)) + + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + } > REGION_TEXT + + /* + * End of text + */ + .text.align : + { + . = ALIGN(8); + __text_end__ = .; + } > REGION_TEXT + + /* + * .ARM.exidx exception unwinding; mandated by ARM's C++ ABI + */ + __exidx_start = .; + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > REGION_RODATA + __exidx_end = .; + + /* + * .data + */ + .data : + { + __data_start__ = .; + LONG(0) + . = ALIGN(8); + + *(.got.plt) *(.got) + *(.data .data.* .gnu.linkonce.d.*) + + . = ALIGN(8); + __data_end__ = .; + } > REGION_DATA AT> REGION_RODATA + + /* + * Read-only data + */ + .rodata : + { + *(.rodata .rodata.* .gnu.linkonce.r.*) + /* .USER_FLASH: We allow users to allocate into Flash here */ + *(.USER_FLASH) + /* ROM image configuration; for C startup */ + . = ALIGN(4); + _lm_rom_img_cfgp = .; + LONG(LOADADDR(.data)); + /* + * Heap: Linker scripts may choose a custom heap by overriding + * _lm_heap_start and _lm_heap_end. Otherwise, the heap is in + * internal SRAM, beginning after .bss, and growing towards + * the stack. + * + * I'm shoving these here naively; there's probably a cleaner way + * to go about this. [mbolivar] + */ + _lm_heap_start = DEFINED(_lm_heap_start) ? _lm_heap_start : _end; + _lm_heap_end = DEFINED(_lm_heap_end) ? _lm_heap_end : __msp_init; + } > REGION_RODATA + + /* + * .bss + */ + .bss : + { + . = ALIGN(8); + __bss_start__ = .; + *(.bss .bss.* .gnu.linkonce.b.*) + *(COMMON) + . = ALIGN (8); + __bss_end__ = .; + _end = __bss_end__; + } > REGION_BSS + + /* + * Debugging sections + */ + .stab 0 (NOLOAD) : { *(.stab) } + .stabstr 0 (NOLOAD) : { *(.stabstr) } + /* DWARF debug sections. + * Symbols in the DWARF debugging sections are relative to the beginning + * of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } + + .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) } + .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) } + /DISCARD/ : { *(.note.GNU-stack) } +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/extra_libs.inc b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/extra_libs.inc new file mode 100644 index 0000000000..dd2c84fa45 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/extra_libs.inc @@ -0,0 +1,7 @@ +/* + * Extra archives needed by ARM's GCC ARM Embedded arm-none-eabi- + * releases (https://launchpad.net/gcc-arm-embedded/). + */ + +/* This is for the provided newlib. */ +GROUP(libnosys.a) diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/flash.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/flash.ld new file mode 100644 index 0000000000..9e250cd747 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/flash.ld @@ -0,0 +1,26 @@ +/* + * libmaple linker script for "Flash" builds. + * + * A Flash build puts .text (and .rodata) in Flash, and + * .data/.bss/heap (of course) in SRAM, but offsets the sections by + * enough space to store the Maple bootloader, which lives in low + * Flash and uses low memory. + */ + +/* + * This pulls in the appropriate MEMORY declaration from the right + * subdirectory of stm32/mem/ (the environment must call ld with the + * right include directory flags to make this happen). Boards can also + * use this file to use any of libmaple's memory-related hooks (like + * where the heap should live). + */ +INCLUDE mem-flash.inc + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/jtag.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/jtag.ld new file mode 100644 index 0000000000..0612f95862 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/jtag.ld @@ -0,0 +1,31 @@ +/* + * libmaple linker script for "JTAG" builds. + * + * A "JTAG" build puts .text (and .rodata) in Flash, and + * .data/.bss/heap (of course) in SRAM, but links starting at the + * Flash and SRAM starting addresses (0x08000000 and 0x20000000 + * respectively). This will wipe out a Maple bootloader if there's one + * on the board, so only use this if you know what you're doing. + * + * Of course, a "JTAG" build is perfectly usable for upload over SWD, + * the system memory bootloader, etc. The name is just a historical + * artifact. + */ + +/* + * This pulls in the appropriate MEMORY declaration from the right + * subdirectory of stm32/mem/ (the environment must call ld with the + * right include directory flags to make this happen). Boards can also + * use this file to use any of libmaple's memory-related hooks (like + * where the heap should live). + */ +INCLUDE mem-jtag.inc + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-flash.inc b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-flash.inc new file mode 100644 index 0000000000..ddb8876fa5 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-flash.inc @@ -0,0 +1,5 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 61K + rom (rx) : ORIGIN = 0x08005000, LENGTH = 492K +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-jtag.inc b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-jtag.inc new file mode 100644 index 0000000000..d3ed992481 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-jtag.inc @@ -0,0 +1,5 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-ram.inc b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-ram.inc new file mode 100644 index 0000000000..360beafe9d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/mem-ram.inc @@ -0,0 +1,5 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 61K + rom (rx) : ORIGIN = 0x08005000, LENGTH = 0K +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/ram.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/ram.ld new file mode 100644 index 0000000000..34b468e0a0 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/ram.ld @@ -0,0 +1,25 @@ +/* + * libmaple linker script for RAM builds. + * + * A Flash build puts .text, .rodata, and .data/.bss/heap (of course) + * in SRAM, but offsets the sections by enough space to store the + * Maple bootloader, which uses low memory. + */ + +/* + * This pulls in the appropriate MEMORY declaration from the right + * subdirectory of stm32/mem/ (the environment must call ld with the + * right include directory flags to make this happen). Boards can also + * use this file to use any of libmaple's memory-related hooks (like + * where the heap should live). + */ +INCLUDE mem-ram.inc + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", ram); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", ram); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld new file mode 100644 index 0000000000..9c0d19b716 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld @@ -0,0 +1,18 @@ +/* + * Linker script for Generic STM32F103RB boards. + */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K + rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K +} + + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb_bootloader.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb_bootloader.ld new file mode 100644 index 0000000000..d045db9f4b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb_bootloader.ld @@ -0,0 +1,17 @@ +/* + * Linker script for Generic STM32F103RB boards, using the generic bootloader (which takes the lower 8k of memory) + */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K + rom (rx) : ORIGIN = 0x08002000, LENGTH = 120K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld new file mode 100644 index 0000000000..016d59d00d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld @@ -0,0 +1,18 @@ +/* + * Linker script for Generic STM32F103RC boards. + */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K + rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K +} + + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc_bootloader.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc_bootloader.ld new file mode 100644 index 0000000000..00b811b0e6 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc_bootloader.ld @@ -0,0 +1,18 @@ +/* + * Linker script for Generic STM32F103RC boards, using the generic bootloader (which takes the lower 8k of memory) + */ + +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K + rom (rx) : ORIGIN = 0x08002000, LENGTH = 248K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld new file mode 100644 index 0000000000..52abb5ad09 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld @@ -0,0 +1,18 @@ +/* + * Linker script for Generic STM32F103RE boards. + */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K +} + + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/vector_symbols.inc b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/vector_symbols.inc new file mode 100644 index 0000000000..f8519bba44 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/vector_symbols.inc @@ -0,0 +1,78 @@ +EXTERN(__msp_init) +EXTERN(__exc_reset) +EXTERN(__exc_nmi) +EXTERN(__exc_hardfault) +EXTERN(__exc_memmanage) +EXTERN(__exc_busfault) +EXTERN(__exc_usagefault) +EXTERN(__stm32reservedexception7) +EXTERN(__stm32reservedexception8) +EXTERN(__stm32reservedexception9) +EXTERN(__stm32reservedexception10) +EXTERN(__exc_svc) +EXTERN(__exc_debug_monitor) +EXTERN(__stm32reservedexception13) +EXTERN(__exc_pendsv) +EXTERN(__exc_systick) + +EXTERN(__irq_wwdg) +EXTERN(__irq_pvd) +EXTERN(__irq_tamper) +EXTERN(__irq_rtc) +EXTERN(__irq_flash) +EXTERN(__irq_rcc) +EXTERN(__irq_exti0) +EXTERN(__irq_exti1) +EXTERN(__irq_exti2) +EXTERN(__irq_exti3) +EXTERN(__irq_exti4) +EXTERN(__irq_dma1_channel1) +EXTERN(__irq_dma1_channel2) +EXTERN(__irq_dma1_channel3) +EXTERN(__irq_dma1_channel4) +EXTERN(__irq_dma1_channel5) +EXTERN(__irq_dma1_channel6) +EXTERN(__irq_dma1_channel7) +EXTERN(__irq_adc) +EXTERN(__irq_usb_hp_can_tx) +EXTERN(__irq_usb_lp_can_rx0) +EXTERN(__irq_can_rx1) +EXTERN(__irq_can_sce) +EXTERN(__irq_exti9_5) +EXTERN(__irq_tim1_brk) +EXTERN(__irq_tim1_up) +EXTERN(__irq_tim1_trg_com) +EXTERN(__irq_tim1_cc) +EXTERN(__irq_tim2) +EXTERN(__irq_tim3) +EXTERN(__irq_tim4) +EXTERN(__irq_i2c1_ev) +EXTERN(__irq_i2c1_er) +EXTERN(__irq_i2c2_ev) +EXTERN(__irq_i2c2_er) +EXTERN(__irq_spi1) +EXTERN(__irq_spi2) +EXTERN(__irq_usart1) +EXTERN(__irq_usart2) +EXTERN(__irq_usart3) +EXTERN(__irq_exti15_10) +EXTERN(__irq_rtcalarm) +EXTERN(__irq_usbwakeup) + +EXTERN(__irq_tim8_brk) +EXTERN(__irq_tim8_up) +EXTERN(__irq_tim8_trg_com) +EXTERN(__irq_tim8_cc) +EXTERN(__irq_adc3) +EXTERN(__irq_fsmc) +EXTERN(__irq_sdio) +EXTERN(__irq_tim5) +EXTERN(__irq_spi3) +EXTERN(__irq_uart4) +EXTERN(__irq_uart5) +EXTERN(__irq_tim6) +EXTERN(__irq_tim7) +EXTERN(__irq_dma2_channel1) +EXTERN(__irq_dma2_channel2) +EXTERN(__irq_dma2_channel3) +EXTERN(__irq_dma2_channel4_5) diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/pins_arduino.h b/buildroot/share/PlatformIO/variants/MEEB_3DP/pins_arduino.h new file mode 100644 index 0000000000..d5dce114d5 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/pins_arduino.h @@ -0,0 +1,2 @@ +// API compatibility +#include "variant.h" diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/variant.h b/buildroot/share/PlatformIO/variants/MEEB_3DP/variant.h new file mode 100644 index 0000000000..f9a545bf6c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/variant.h @@ -0,0 +1,20 @@ +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#define digitalPinToPort(P) ( PIN_MAP[P].gpio_device ) +#define digitalPinToBitMask(P) ( BIT(PIN_MAP[P].gpio_bit) ) +#define portOutputRegister(port) ( &(port->regs->ODR) ) +#define portInputRegister(port) ( &(port->regs->IDR) ) + +#define portSetRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BSRR) ) +#define portClearRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BRR) ) + +#define portConfigRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->CRL) ) + +static const uint8_t SS = BOARD_SPI1_NSS_PIN; +static const uint8_t SS1 = BOARD_SPI2_NSS_PIN; +static const uint8_t MOSI = BOARD_SPI1_MOSI_PIN; +static const uint8_t MISO = BOARD_SPI1_MISO_PIN; +static const uint8_t SCK = BOARD_SPI1_SCK_PIN; + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp new file mode 100644 index 0000000000..feb287d6f3 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards.cpp @@ -0,0 +1,225 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * Copyright (c) 2011, 2012 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish/boards.cpp + * @brief init() and board routines. + * + * This file is mostly interesting for the init() function, which + * configures Flash, the core clocks, and a variety of other available + * peripherals on the board so the rest of Wirish doesn't have to turn + * things on before using them. + * + * Prior to returning, init() calls boardInit(), which allows boards + * to perform any initialization they need to. This file includes a + * weak no-op definition of boardInit(), so boards that don't need any + * special initialization don't have to define their own. + * + * How init() works is chip-specific. See the boards_setup.cpp files + * under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be + * advised: their contents are unstable, and can/will change without + * notice. + */ + +#include +#include +#include +#include +#include +#include "boards_private.h" + +static void setup_flash(void); +static void setup_clocks(void); +static void setup_nvic(void); +static void setup_adcs(void); +static void setup_timers(void); + +/* + * Exported functions + */ + +void init(void) { + setup_flash(); + setup_clocks(); + setup_nvic(); + systick_init(SYSTICK_RELOAD_VAL); + wirish::priv::board_setup_gpio(); + setup_adcs(); + setup_timers(); + wirish::priv::board_setup_usb(); + wirish::priv::series_init(); + boardInit(); +} + +/* Provide a default no-op boardInit(). */ +__weak void boardInit(void) { +} + +/* You could farm this out to the files in boards/ if e.g. it takes + * too long to test on boards with lots of pins. */ +bool boardUsesPin(uint8 pin) { + for (int i = 0; i < BOARD_NR_USED_PINS; i++) { + if (pin == boardUsedPins[i]) { + return true; + } + } + return false; +} + +/* + * Auxiliary routines + */ + +static void setup_flash(void) { + // Turn on as many Flash "go faster" features as + // possible. flash_enable_features() just ignores any flags it + // can't support. + flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE); + // Configure the wait states, assuming we're operating at "close + // enough" to 3.3V. + flash_set_latency(FLASH_SAFE_WAIT_STATES); +} + +static void setup_clocks(void) { + // Turn on HSI. We'll switch to and run off of this while we're + // setting up the main PLL. + rcc_turn_on_clk(RCC_CLK_HSI); + + // Turn off and reset the clock subsystems we'll be using, as well + // as the clock security subsystem (CSS). Note that resetting CFGR + // to its default value of 0 implies a switch to HSI for SYSCLK. + RCC_BASE->CFGR = 0x00000000; + rcc_disable_css(); + rcc_turn_off_clk(RCC_CLK_PLL); + rcc_turn_off_clk(RCC_CLK_HSE); + wirish::priv::board_reset_pll(); + // Clear clock readiness interrupt flags and turn off clock + // readiness interrupts. + RCC_BASE->CIR = 0x00000000; +#if !USE_HSI_CLOCK + // Enable HSE, and wait until it's ready. + rcc_turn_on_clk(RCC_CLK_HSE); + while (!rcc_is_clk_ready(RCC_CLK_HSE)) + ; +#endif + // Configure AHBx, APBx, etc. prescalers and the main PLL. + wirish::priv::board_setup_clock_prescalers(); + rcc_configure_pll(&wirish::priv::w_board_pll_cfg); + + // Enable the PLL, and wait until it's ready. + rcc_turn_on_clk(RCC_CLK_PLL); + while(!rcc_is_clk_ready(RCC_CLK_PLL)) + ; + + // Finally, switch to the now-ready PLL as the main clock source. + rcc_switch_sysclk(RCC_CLKSRC_PLL); +} + +/* + * These addresses are where usercode starts when a bootloader is + * present. If no bootloader is present, the user NVIC usually starts + * at the Flash base address, 0x08000000. + */ +#if defined(BOOTLOADER_maple) + #define USER_ADDR_ROM 0x08002000 +#else + #define USER_ADDR_ROM 0x08000000 +#endif +#define USER_ADDR_RAM 0x20000C00 +extern char __text_start__; + +static void setup_nvic(void) { + +nvic_init((uint32)VECT_TAB_ADDR, 0); + +/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater +#ifdef VECT_TAB_FLASH + nvic_init(USER_ADDR_ROM, 0); +#elif defined VECT_TAB_RAM + nvic_init(USER_ADDR_RAM, 0); +#elif defined VECT_TAB_BASE + nvic_init((uint32)0x08000000, 0); +#elif defined VECT_TAB_ADDR + // A numerically supplied value + nvic_init((uint32)VECT_TAB_ADDR, 0); +#else + // Use the __text_start__ value from the linker script; this + // should be the start of the vector table. + nvic_init((uint32)&__text_start__, 0); +#endif + +*/ +} + +static void adc_default_config(adc_dev *dev) { + adc_enable_single_swstart(dev); + adc_set_sample_rate(dev, wirish::priv::w_adc_smp); +} + +static void setup_adcs(void) { + adc_set_prescaler(wirish::priv::w_adc_pre); + adc_foreach(adc_default_config); +} + +static void timer_default_config(timer_dev *dev) { + timer_adv_reg_map *regs = (dev->regs).adv; + const uint16 full_overflow = 0xFFFF; + const uint16 half_duty = 0x8FFF; + + timer_init(dev); + timer_pause(dev); + + regs->CR1 = TIMER_CR1_ARPE; + regs->PSC = 1; + regs->SR = 0; + regs->DIER = 0; + regs->EGR = TIMER_EGR_UG; + switch (dev->type) { + case TIMER_ADVANCED: + regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; + // fall-through + case TIMER_GENERAL: + timer_set_reload(dev, full_overflow); + for (uint8 channel = 1; channel <= 4; channel++) { + if (timer_has_cc_channel(dev, channel)) { + timer_set_compare(dev, channel, half_duty); + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, + TIMER_OC_PE); + } + } + // fall-through + case TIMER_BASIC: + break; + } + + timer_generate_update(dev); + timer_resume(dev); +} + +static void setup_timers(void) { + timer_foreach(timer_default_config); +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp new file mode 100644 index 0000000000..d4e95925ac --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp @@ -0,0 +1,106 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2012 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. +*****************************************************************************/ + +/** + * @file wirish/stm32f1/boards_setup.cpp + * @author Marti Bolivar + * @brief STM32F1 chip setup. + * + * This file controls how init() behaves on the STM32F1. Be very + * careful when changing anything here. Many of these values depend + * upon each other. + */ + +#include "boards_private.h" + +#include +#include + +#include +#include + +// Allow boards to provide a PLL multiplier. This is useful for +// e.g. STM32F100 value line MCUs, which use slower multipliers. +// (We're leaving the default to RCC_PLLMUL_9 for now, since that +// works for F103 performance line MCUs, which is all that LeafLabs +// currently officially supports). + +namespace wirish { + namespace priv { + + static stm32f1_rcc_pll_data pll_data = {RCC_PLLMUL_6}; +#if !USE_HSI_CLOCK + __weak rcc_pll_cfg w_board_pll_cfg = {RCC_PLLSRC_HSE, &pll_data}; +#else + __weak rcc_pll_cfg w_board_pll_cfg = {RCC_PLLSRC_HSI_DIV_2, &pll_data}; +#endif + __weak adc_prescaler w_adc_pre = ADC_PRE_PCLK2_DIV_6; + __weak adc_smp_rate w_adc_smp = ADC_SMPR_55_5; + + __weak void board_reset_pll(void) { + // TODO + } + + __weak void board_setup_clock_prescalers(void) { + rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); + rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); + rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); + rcc_clk_disable(RCC_USB); + #if F_CPU == 72000000 + rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1_5); + #elif F_CPU == 48000000 + rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1); + #endif + } + + __weak void board_setup_gpio(void) { + gpio_init_all(); + } + + __weak void board_setup_usb(void) { +#ifdef SERIAL_USB + +#ifdef GENERIC_BOOTLOADER + //Reset the USB interface on generic boards - developed by Victor PV + gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_OUTPUT_PP); + gpio_write_bit(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit,0); + + for(volatile unsigned int i=0;i<512;i++);// Only small delay seems to be needed, and USB pins will get configured in Serial.begin + gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_INPUT_FLOATING); +#endif + + Serial.begin();// Roger Clark. Changed SerialUSB to Serial for Arduino sketch compatibility +#endif + } + + __weak void series_init(void) { + // Initialize AFIO here, too, so peripheral remaps and external + // interrupts work out of the box. + afio_init(); + } + + } +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start.S b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start.S new file mode 100644 index 0000000000..8b181aa993 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start.S @@ -0,0 +1,57 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/* + * This file is a modified version of a file obtained from + * CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the + * following text appeared: + * + * The authors hereby grant permission to use, copy, modify, distribute, + * and license this software and its documentation for any purpose, provided + * that existing copyright notices are retained in all copies and that this + * notice is included verbatim in any distributions. No written agreement, + * license, or royalty fee is required for any of the authorized uses. + * Modifications to this software may be copyrighted by their authors + * and need not follow the licensing terms described here, provided that + * the new terms are clearly indicated on the first page of each file where + * they apply. + */ + + .text + .code 16 + .thumb_func + + .globl __start__ + .type __start__, %function +__start__: + .fnstart + ldr r1,=__msp_init + mov sp,r1 + ldr r1,=start_c + bx r1 + .pool + .cantunwind + .fnend diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start_c.c b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start_c.c new file mode 100644 index 0000000000..655fefb884 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/start_c.c @@ -0,0 +1,95 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/* + * This file is a modified version of a file obtained from + * CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the + * following text appeared: + * + * Copyright (c) 2006, 2007 CodeSourcery Inc + * + * The authors hereby grant permission to use, copy, modify, distribute, + * and license this software and its documentation for any purpose, provided + * that existing copyright notices are retained in all copies and that this + * notice is included verbatim in any distributions. No written agreement, + * license, or royalty fee is required for any of the authorized uses. + * Modifications to this software may be copyrighted by their authors + * and need not follow the licensing terms described here, provided that + * the new terms are clearly indicated on the first page of each file where + * they apply. + */ + +#include + +extern void __libc_init_array(void); + +extern int main(int, char**, char**); + +extern void exit(int) __attribute__((noreturn, weak)); + +/* The linker must ensure that these are at least 4-byte aligned. */ +extern char __data_start__, __data_end__; +extern char __bss_start__, __bss_end__; + +struct rom_img_cfg { + int *img_start; +}; + +extern char _lm_rom_img_cfgp; + +void __attribute__((noreturn)) start_c(void) { + struct rom_img_cfg *img_cfg = (struct rom_img_cfg*)&_lm_rom_img_cfgp; + int *src = img_cfg->img_start; + int *dst = (int*)&__data_start__; + int exit_code; + + /* Initialize .data, if necessary. */ + if (src != dst) { + int *end = (int*)&__data_end__; + while (dst < end) { + *dst++ = *src++; + } + } + + /* Zero .bss. */ + dst = (int*)&__bss_start__; + while (dst < (int*)&__bss_end__) { + *dst++ = 0; + } + + /* Run initializers. */ + __libc_init_array(); + + /* Jump to main. */ + exit_code = main(0, 0, 0); + if (exit) { + exit(exit_code); + } + + /* If exit is NULL, make sure we don't return. */ + for (;;) + continue; +} diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/syscalls.c b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/syscalls.c new file mode 100644 index 0000000000..d5f2d9fac3 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/syscalls.c @@ -0,0 +1,176 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * Copyright (c) 2011, 2012 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish/syscalls.c + * @brief newlib stubs + * + * Low level system routines used by newlib for basic I/O and memory + * allocation. You can override most of these. + */ + +#include + +#include +#include +#include + +/* If CONFIG_HEAP_START (or CONFIG_HEAP_END) isn't defined, then + * assume _lm_heap_start (resp. _lm_heap_end) is appropriately set by + * the linker */ +#ifndef CONFIG_HEAP_START +extern char _lm_heap_start; +#define CONFIG_HEAP_START ((void *)&_lm_heap_start) +#endif +#ifndef CONFIG_HEAP_END +extern char _lm_heap_end; +#define CONFIG_HEAP_END ((void *)&_lm_heap_end) +#endif + +/* + * _sbrk -- Increment the program break. + * + * Get incr bytes more RAM (for use by the heap). malloc() and + * friends call this function behind the scenes. + */ +void *_sbrk(int incr) { + static void * pbreak = NULL; /* current program break */ + void * ret; + + if (pbreak == NULL) { + pbreak = CONFIG_HEAP_START; + } + + if ((CONFIG_HEAP_END - pbreak < incr) || + (pbreak - CONFIG_HEAP_START < -incr)) { + errno = ENOMEM; + return (void *)-1; + } + + ret = pbreak; + pbreak += incr; + return ret; +} + +__weak int _open(const char *path, int flags, ...) { + return 1; +} + +__weak int _close(int fd) { + return 0; +} + +__weak int _fstat(int fd, struct stat *st) { + st->st_mode = S_IFCHR; + return 0; +} + +__weak int _isatty(int fd) { + return 1; +} + +__weak int isatty(int fd) { + return 1; +} + +__weak int _lseek(int fd, off_t pos, int whence) { + return -1; +} + +__weak unsigned char getch(void) { + return 0; +} + + +__weak int _read(int fd, char *buf, size_t cnt) { + *buf = getch(); + + return 1; +} + +__weak void putch(unsigned char c) { +} + +__weak void cgets(char *s, int bufsize) { + char *p; + int c; + int i; + + for (i = 0; i < bufsize; i++) { + *(s+i) = 0; + } +// memset(s, 0, bufsize); + + p = s; + + for (p = s; p < s + bufsize-1;) { + c = getch(); + switch (c) { + case '\r' : + case '\n' : + putch('\r'); + putch('\n'); + *p = '\n'; + return; + + case '\b' : + if (p > s) { + *p-- = 0; + putch('\b'); + putch(' '); + putch('\b'); + } + break; + + default : + putch(c); + *p++ = c; + break; + } + } + return; +} + +__weak int _write(int fd, const char *buf, size_t cnt) { + int i; + + for (i = 0; i < cnt; i++) + putch(buf[i]); + + return cnt; +} + +/* Override fgets() in newlib with a version that does line editing */ +__weak char *fgets(char *s, int bufsize, void *f) { + cgets(s, bufsize); + return s; +} + +__weak void _exit(int exitcode) { + while (1) + ; +} diff --git a/buildroot/share/tests/STM32F103RC_cc_meeb_3dp-tests b/buildroot/share/tests/STM32F103RC_cc_meeb_3dp-tests new file mode 100644 index 0000000000..74e770d3c8 --- /dev/null +++ b/buildroot/share/tests/STM32F103RC_cc_meeb_3dp-tests @@ -0,0 +1,23 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC MEEB_3DP (ccrobot-online.com) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_CCROBOT_MEEB_3DP +opt_set SERIAL_PORT 1 +opt_set SERIAL_PORT_2 -1 +opt_set X_DRIVER_TYPE TMC2208 +opt_set Y_DRIVER_TYPE TMC2208 +opt_set Z_DRIVER_TYPE TMC2208 +opt_set E0_DRIVER_TYPE TMC2208 +exec_test $1 $2 "MEEB_3DP - Basic Config with TMC2208 SW Serial" + +# clean up +restore_configs diff --git a/platformio.ini b/platformio.ini index aa8dd21983..fa27fb9a9a 100644 --- a/platformio.ini +++ b/platformio.ini @@ -45,15 +45,7 @@ src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel SPI -lib_deps = - LiquidCrystal - TMCStepper@>=0.6.2 - U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip - Adafruit MAX31865 library@>=1.1,<1.2 - LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip - Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/0.8.0.zip - SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip - SlowSoftI2CMaster=https://github.com/mikeshub/SlowSoftI2CMaster/archive/master.zip +lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip [common_avr8] @@ -287,6 +279,31 @@ board = genericSTM32F103RC platform_packages = tool-stm32duino monitor_speed = 115200 +# +# MEEB_3DP (STM32F103RCT6 with 512K) +# +[env:STM32F103RC_cc_meeb_3dp] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = MEEB_3DP +platform_packages = tool-stm32duino +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 + -DSS_TIMER=4 + -DSTM32_FLASH_SIZE=512 + -DHSE_VALUE=12000000U + -DUSE_USB_COMPOSITE + -DVECT_TAB_OFFSET=0x2000 + -DGENERIC_BOOTLOADER +extra_scripts = pre:buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py + buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +lib_deps = ${common.lib_deps} + USBComposite for STM32F1@==0.91 + Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use +lib_ignore = SPI, LiquidCrystal +debug_tool = stlink +upload_protocol = dfu + # # STM32F103RC_fysetc # From 33d1e77e2e252f3a3825941630718ea7d8f67451 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 2 Jun 2020 11:33:30 +1200 Subject: [PATCH 0561/1454] Allow pins override of *_TIMER_NUM and HAL_*_TIMER_ISR (#18128) Co-authored-by: Scott Lahteine --- Marlin/src/HAL/AVR/HAL.h | 217 --------------- Marlin/src/HAL/AVR/timers.h | 259 ++++++++++++++++++ Marlin/src/HAL/DUE/HAL.h | 1 - Marlin/src/HAL/DUE/Tone.cpp | 1 - Marlin/src/HAL/DUE/timers.cpp | 2 - Marlin/src/HAL/DUE/timers.h | 22 +- Marlin/src/HAL/ESP32/HAL.cpp | 6 +- Marlin/src/HAL/ESP32/HAL.h | 2 - Marlin/src/HAL/ESP32/HAL_SPI.cpp | 11 +- Marlin/src/HAL/ESP32/timers.cpp | 4 +- Marlin/src/HAL/ESP32/timers.h | 28 +- Marlin/src/HAL/LINUX/HAL.h | 1 - Marlin/src/HAL/LINUX/timers.cpp | 1 - Marlin/src/HAL/LINUX/timers.h | 20 +- Marlin/src/HAL/LPC1768/HAL.h | 1 - Marlin/src/HAL/LPC1768/main.cpp | 2 - Marlin/src/HAL/LPC1768/timers.cpp | 1 - Marlin/src/HAL/LPC1768/timers.h | 24 +- Marlin/src/HAL/SAMD51/HAL.h | 1 - Marlin/src/HAL/SAMD51/Servo.cpp | 1 - Marlin/src/HAL/SAMD51/timers.cpp | 1 - Marlin/src/HAL/SAMD51/timers.h | 26 +- Marlin/src/HAL/STM32/HAL.h | 1 - Marlin/src/HAL/STM32/SoftwareSerial.cpp | 3 +- Marlin/src/HAL/STM32/timers.cpp | 2 - Marlin/src/HAL/STM32/timers.h | 21 +- Marlin/src/HAL/STM32F1/HAL.h | 1 - Marlin/src/HAL/STM32F1/Servo.cpp | 1 - Marlin/src/HAL/STM32F1/timers.cpp | 2 - Marlin/src/HAL/STM32F1/timers.h | 28 +- Marlin/src/HAL/STM32_F4_F7/HAL.h | 1 - Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp | 3 +- Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h | 30 +- Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp | 3 +- Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h | 20 +- Marlin/src/HAL/TEENSY31_32/HAL.h | 1 - Marlin/src/HAL/TEENSY31_32/timers.cpp | 3 +- Marlin/src/HAL/TEENSY31_32/timers.h | 20 +- Marlin/src/HAL/TEENSY35_36/HAL.h | 2 - Marlin/src/HAL/TEENSY35_36/timers.cpp | 3 +- Marlin/src/HAL/TEENSY35_36/timers.h | 20 +- Marlin/src/inc/MarlinConfig.h | 1 + Marlin/src/pins/sam/pins_ARCHIM1.h | 1 + 43 files changed, 461 insertions(+), 338 deletions(-) create mode 100644 Marlin/src/HAL/AVR/timers.h diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index e96193651b..b7e05a956d 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -68,9 +68,6 @@ // Types // ------------------------ -typedef uint16_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFF - typedef int8_t pin_t; #define SHARED_SERVOS HAS_SERVOS @@ -143,220 +140,6 @@ extern "C" { } #pragma GCC diagnostic pop -// timers -#define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz - -#define STEP_TIMER_NUM 1 -#define TEMP_TIMER_NUM 0 -#define PULSE_TIMER_NUM STEP_TIMER_NUM - -#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0) - -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_PRESCALE 8 -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double - -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US - -#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) -#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A) - -#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B) -#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B) -#define TEMPERATURE_ISR_ENABLED() TEST(TIMSK0, OCIE0B) - -FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { - switch (timer_num) { - case STEP_TIMER_NUM: - // waveform generation = 0100 = CTC - SET_WGM(1, CTC_OCRnA); - - // output mode = 00 (disconnected) - SET_COMA(1, NORMAL); - - // Set the timer pre-scaler - // Generally we use a divider of 8, resulting in a 2MHz timer - // frequency on a 16MHz MCU. If you are going to change this, be - // sure to regenerate speed_lookuptable.h with - // create_speed_lookuptable.py - SET_CS(1, PRESCALER_8); // CS 2 = 1/8 prescaler - - // Init Stepper ISR to 122 Hz for quick starting - // (F_CPU) / (STEPPER_TIMER_PRESCALE) / frequency - OCR1A = 0x4000; - TCNT1 = 0; - break; - - case TEMP_TIMER_NUM: - // Use timer0 for temperature measurement - // Interleave temperature interrupt with millies interrupt - OCR0B = 128; - break; - } -} - -#define TIMER_OCR_1 OCR1A -#define TIMER_COUNTER_1 TCNT1 - -#define TIMER_OCR_0 OCR0A -#define TIMER_COUNTER_0 TCNT0 - -#define _CAT(a,V...) a##V -#define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare) -#define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer) -#define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer) - -/** - * On AVR there is no hardware prioritization and preemption of - * interrupts, so this emulates it. The UART has first priority - * (otherwise, characters will be lost due to UART overflow). - * Then: Stepper, Endstops, Temperature, and -finally- all others. - */ -#define HAL_timer_isr_prologue(TIMER_NUM) -#define HAL_timer_isr_epilogue(TIMER_NUM) - -/* 18 cycles maximum latency */ -#define HAL_STEP_TIMER_ISR() \ -extern "C" void TIMER1_COMPA_vect() __attribute__ ((signal, naked, used, externally_visible)); \ -extern "C" void TIMER1_COMPA_vect_bottom() asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \ -void TIMER1_COMPA_vect() { \ - __asm__ __volatile__ ( \ - A("push r16") /* 2 Save R16 */ \ - A("in r16, __SREG__") /* 1 Get SREG */ \ - A("push r16") /* 2 Save SREG into stack */ \ - A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \ - A("push r16") /* 2 Save TIMSK0 into the stack */ \ - A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \ - A("sts %[timsk0], r16") /* 2 And set the new value */ \ - A("lds r16, %[timsk1]") /* 2 Load into R0 the stepper timer Interrupt mask register [TIMSK1] */ \ - A("andi r16,~%[msk1]") /* 1 Disable the stepper ISR */ \ - A("sts %[timsk1], r16") /* 2 And set the new value */ \ - A("push r16") /* 2 Save TIMSK1 into stack */ \ - A("in r16, 0x3B") /* 1 Get RAMPZ register */ \ - A("push r16") /* 2 Save RAMPZ into stack */ \ - A("in r16, 0x3C") /* 1 Get EIND register */ \ - A("push r0") /* C runtime can modify all the following registers without restoring them */ \ - A("push r1") \ - A("push r18") \ - A("push r19") \ - A("push r20") \ - A("push r21") \ - A("push r22") \ - A("push r23") \ - A("push r24") \ - A("push r25") \ - A("push r26") \ - A("push r27") \ - A("push r30") \ - A("push r31") \ - A("clr r1") /* C runtime expects this register to be 0 */ \ - A("call TIMER1_COMPA_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \ - A("pop r31") \ - A("pop r30") \ - A("pop r27") \ - A("pop r26") \ - A("pop r25") \ - A("pop r24") \ - A("pop r23") \ - A("pop r22") \ - A("pop r21") \ - A("pop r20") \ - A("pop r19") \ - A("pop r18") \ - A("pop r1") \ - A("pop r0") \ - A("out 0x3C, r16") /* 1 Restore EIND register */ \ - A("pop r16") /* 2 Get the original RAMPZ register value */ \ - A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \ - A("pop r16") /* 2 Get the original TIMSK1 value but with stepper ISR disabled */ \ - A("ori r16,%[msk1]") /* 1 Reenable the stepper ISR */ \ - A("cli") /* 1 Disable global interrupts - Reenabling Stepper ISR can reenter amd temperature can reenter, and we want that, if it happens, after this ISR has ended */ \ - A("sts %[timsk1], r16") /* 2 And restore the old value - This reenables the stepper ISR */ \ - A("pop r16") /* 2 Get the temperature timer Interrupt mask register [TIMSK0] */ \ - A("sts %[timsk0], r16") /* 2 And restore the old value - This reenables the temperature ISR */ \ - A("pop r16") /* 2 Get the old SREG value */ \ - A("out __SREG__, r16") /* 1 And restore the SREG value */ \ - A("pop r16") /* 2 Restore R16 value */ \ - A("reti") /* 4 Return from interrupt */ \ - : \ - : [timsk0] "i" ((uint16_t)&TIMSK0), \ - [timsk1] "i" ((uint16_t)&TIMSK1), \ - [msk0] "M" ((uint8_t)(1<. + */ +#pragma once + +#include + +// ------------------------ +// Types +// ------------------------ + +typedef uint16_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX 0xFFFF + +// ------------------------ +// Defines +// ------------------------ + +#define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz + +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 1 +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 0 +#endif + +#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0) + +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_PRESCALE 8 +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double + +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) +#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A) + +#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B) +#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B) +#define TEMPERATURE_ISR_ENABLED() TEST(TIMSK0, OCIE0B) + +FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { + switch (timer_num) { + case STEP_TIMER_NUM: + // waveform generation = 0100 = CTC + SET_WGM(1, CTC_OCRnA); + + // output mode = 00 (disconnected) + SET_COMA(1, NORMAL); + + // Set the timer pre-scaler + // Generally we use a divider of 8, resulting in a 2MHz timer + // frequency on a 16MHz MCU. If you are going to change this, be + // sure to regenerate speed_lookuptable.h with + // create_speed_lookuptable.py + SET_CS(1, PRESCALER_8); // CS 2 = 1/8 prescaler + + // Init Stepper ISR to 122 Hz for quick starting + // (F_CPU) / (STEPPER_TIMER_PRESCALE) / frequency + OCR1A = 0x4000; + TCNT1 = 0; + break; + + case TEMP_TIMER_NUM: + // Use timer0 for temperature measurement + // Interleave temperature interrupt with millies interrupt + OCR0B = 128; + break; + } +} + +#define TIMER_OCR_1 OCR1A +#define TIMER_COUNTER_1 TCNT1 + +#define TIMER_OCR_0 OCR0A +#define TIMER_COUNTER_0 TCNT0 + +#define _CAT(a,V...) a##V +#define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare) +#define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer) +#define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer) + +/** + * On AVR there is no hardware prioritization and preemption of + * interrupts, so this emulates it. The UART has first priority + * (otherwise, characters will be lost due to UART overflow). + * Then: Stepper, Endstops, Temperature, and -finally- all others. + */ +#define HAL_timer_isr_prologue(TIMER_NUM) +#define HAL_timer_isr_epilogue(TIMER_NUM) + +/* 18 cycles maximum latency */ +#ifndef HAL_STEP_TIMER_ISR + +#define HAL_STEP_TIMER_ISR() \ +extern "C" void TIMER1_COMPA_vect() __attribute__ ((signal, naked, used, externally_visible)); \ +extern "C" void TIMER1_COMPA_vect_bottom() asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \ +void TIMER1_COMPA_vect() { \ + __asm__ __volatile__ ( \ + A("push r16") /* 2 Save R16 */ \ + A("in r16, __SREG__") /* 1 Get SREG */ \ + A("push r16") /* 2 Save SREG into stack */ \ + A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \ + A("push r16") /* 2 Save TIMSK0 into the stack */ \ + A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \ + A("sts %[timsk0], r16") /* 2 And set the new value */ \ + A("lds r16, %[timsk1]") /* 2 Load into R0 the stepper timer Interrupt mask register [TIMSK1] */ \ + A("andi r16,~%[msk1]") /* 1 Disable the stepper ISR */ \ + A("sts %[timsk1], r16") /* 2 And set the new value */ \ + A("push r16") /* 2 Save TIMSK1 into stack */ \ + A("in r16, 0x3B") /* 1 Get RAMPZ register */ \ + A("push r16") /* 2 Save RAMPZ into stack */ \ + A("in r16, 0x3C") /* 1 Get EIND register */ \ + A("push r0") /* C runtime can modify all the following registers without restoring them */ \ + A("push r1") \ + A("push r18") \ + A("push r19") \ + A("push r20") \ + A("push r21") \ + A("push r22") \ + A("push r23") \ + A("push r24") \ + A("push r25") \ + A("push r26") \ + A("push r27") \ + A("push r30") \ + A("push r31") \ + A("clr r1") /* C runtime expects this register to be 0 */ \ + A("call TIMER1_COMPA_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \ + A("pop r31") \ + A("pop r30") \ + A("pop r27") \ + A("pop r26") \ + A("pop r25") \ + A("pop r24") \ + A("pop r23") \ + A("pop r22") \ + A("pop r21") \ + A("pop r20") \ + A("pop r19") \ + A("pop r18") \ + A("pop r1") \ + A("pop r0") \ + A("out 0x3C, r16") /* 1 Restore EIND register */ \ + A("pop r16") /* 2 Get the original RAMPZ register value */ \ + A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \ + A("pop r16") /* 2 Get the original TIMSK1 value but with stepper ISR disabled */ \ + A("ori r16,%[msk1]") /* 1 Reenable the stepper ISR */ \ + A("cli") /* 1 Disable global interrupts - Reenabling Stepper ISR can reenter amd temperature can reenter, and we want that, if it happens, after this ISR has ended */ \ + A("sts %[timsk1], r16") /* 2 And restore the old value - This reenables the stepper ISR */ \ + A("pop r16") /* 2 Get the temperature timer Interrupt mask register [TIMSK0] */ \ + A("sts %[timsk0], r16") /* 2 And restore the old value - This reenables the temperature ISR */ \ + A("pop r16") /* 2 Get the old SREG value */ \ + A("out __SREG__, r16") /* 1 And restore the SREG value */ \ + A("pop r16") /* 2 Restore R16 value */ \ + A("reti") /* 4 Return from interrupt */ \ + : \ + : [timsk0] "i" ((uint16_t)&TIMSK0), \ + [timsk1] "i" ((uint16_t)&TIMSK1), \ + [msk0] "M" ((uint8_t)(1< diff --git a/Marlin/src/HAL/DUE/Tone.cpp b/Marlin/src/HAL/DUE/Tone.cpp index 9b580b8b4c..ebf4fbcfb6 100644 --- a/Marlin/src/HAL/DUE/Tone.cpp +++ b/Marlin/src/HAL/DUE/Tone.cpp @@ -31,7 +31,6 @@ #include "../../inc/MarlinConfig.h" #include "HAL.h" -#include "timers.h" static pin_t tone_pin; volatile static int32_t toggles; diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index 74ae882843..c49572c735 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -34,8 +34,6 @@ #include "../../inc/MarlinConfig.h" #include "HAL.h" -#include "timers.h" - // ------------------------ // Local defines // ------------------------ diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index 5144660116..4ad766781e 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -40,11 +40,17 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE ((F_CPU) / 2) // frequency of timers peripherals #ifndef STEP_TIMER_NUM -#define STEP_TIMER_NUM 2 // index of timer to use for stepper + #define STEP_TIMER_NUM 2 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 4 // Timer Index for Temperature +#endif +#ifndef TONE_TIMER_NUM + #define TONE_TIMER_NUM 6 // index of timer to use for beeper tones #endif -#define TEMP_TIMER_NUM 4 // index of timer to use for temperature -#define PULSE_TIMER_NUM STEP_TIMER_NUM -#define TONE_TIMER_NUM 6 // index of timer to use for beeper tones #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -66,8 +72,12 @@ typedef uint32_t hal_timer_t; #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() void TC2_Handler() #endif -#define HAL_TEMP_TIMER_ISR() void TC4_Handler() -#define HAL_TONE_TIMER_ISR() void TC6_Handler() +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() void TC4_Handler() +#endif +#ifndef HAL_TONE_TIMER_ISR + #define HAL_TONE_TIMER_ISR() void TC6_Handler() +#endif // ------------------------ // Types diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 4194c531cf..d6dd46feb4 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -21,15 +21,13 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "HAL.h" -#include "timers.h" +#include "../../inc/MarlinConfig.h" + #include #include #include #include -#include "../../inc/MarlinConfigPre.h" - #if ENABLED(WIFISUPPORT) #include #include "wifi.h" diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 4b1ccbf20f..9eed6d9461 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -34,8 +34,6 @@ #include "watchdog.h" #include "i2s.h" -#include "timers.h" - #if ENABLED(WIFISUPPORT) #include "WebSocketSerial.h" #endif diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 27414cf6f8..f8f08fe6e0 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -22,13 +22,12 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "HAL.h" -#include "../shared/HAL_SPI.h" -#include -#include "spi_pins.h" -#include +#include "../../inc/MarlinConfig.h" -#include "../../core/macros.h" +#include "../shared/HAL_SPI.h" + +#include +#include // ------------------------ // Public Variables diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp index ad897661c6..6a158001b7 100644 --- a/Marlin/src/HAL/ESP32/timers.cpp +++ b/Marlin/src/HAL/ESP32/timers.cpp @@ -27,9 +27,7 @@ #include #include -#include "HAL.h" - -#include "timers.h" +#include "../../inc/MarlinConfig.h" // ------------------------ // Local defines diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index bc4306be20..dcc195ae09 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -38,10 +38,18 @@ typedef uint64_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL -#define STEP_TIMER_NUM 0 // index of timer to use for stepper -#define TEMP_TIMER_NUM 1 // index of timer to use for temperature -#define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif +#ifndef PWM_TIMER_NUM + #define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs +#endif #define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals @@ -79,9 +87,15 @@ typedef uint64_t hal_timer_t; #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) -#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() -#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() -#define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler() +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() +#endif +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() +#endif +#ifndef HAL_PWM_TIMER_ISR + #define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler() +#endif extern "C" void tempTC_Handler(); extern "C" void stepTC_Handler(); diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 88a57d7416..ba9a785ce1 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -56,7 +56,6 @@ uint8_t _getc(); #include "../shared/HAL_SPI.h" #include "fastio.h" #include "watchdog.h" -#include "timers.h" #include "serial.h" #define SHARED_SERVOS HAS_SERVOS diff --git a/Marlin/src/HAL/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp index 4ccffa63c5..83797bb644 100644 --- a/Marlin/src/HAL/LINUX/timers.cpp +++ b/Marlin/src/HAL/LINUX/timers.cpp @@ -24,7 +24,6 @@ #include "hardware/Timer.h" #include "../../inc/MarlinConfig.h" -#include "timers.h" /** * Use POSIX signals to attempt to emulate Interrupts diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index b657584922..bb7821aa39 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -37,9 +37,15 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals -#define STEP_TIMER_NUM 0 // Timer Index for Stepper -#define TEMP_TIMER_NUM 1 // Timer Index for Temperature -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif #define TEMP_TIMER_RATE 1000000 #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -59,8 +65,12 @@ typedef uint32_t hal_timer_t; #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) -#define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler() -#define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler() +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler() +#endif // PWM timer #define HAL_PWM_TIMER diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 162da8b56d..66c55bb718 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -41,7 +41,6 @@ extern "C" volatile uint32_t _millis; #include "../shared/HAL_SPI.h" #include "fastio.h" #include "watchdog.h" -#include "timers.h" #include "MarlinSerial.h" #include diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index d7b05dce9d..335792ec45 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -38,8 +38,6 @@ extern "C" { #include "../../sd/cardreader.h" #include "../../inc/MarlinConfig.h" #include "../../core/millis_t.h" -#include "HAL.h" -#include "timers.h" extern uint32_t MSC_SD_Init(uint8_t pdrv); extern "C" int isLPC1769(); diff --git a/Marlin/src/HAL/LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp index 686b251c69..5a8f54a1d4 100644 --- a/Marlin/src/HAL/LPC1768/timers.cpp +++ b/Marlin/src/HAL/LPC1768/timers.cpp @@ -29,7 +29,6 @@ #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfig.h" -#include "timers.h" void HAL_timer_init() { SBI(LPC_SC->PCONP, SBIT_TIMER0); // Power ON Timer 0 diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index f99418c1c3..e9def8131c 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -61,10 +61,18 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals -#define STEP_TIMER_NUM 0 // Timer Index for Stepper -#define TEMP_TIMER_NUM 1 // Timer Index for Temperature -#define PULSE_TIMER_NUM STEP_TIMER_NUM -#define PWM_TIMER_NUM 3 // Timer Index for PWM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif +#ifndef PWM_TIMER_NUM + #define PWM_TIMER_NUM 3 // Timer Index for PWM +#endif #define TEMP_TIMER_RATE 1000000 #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -84,8 +92,12 @@ typedef uint32_t hal_timer_t; #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) -#define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM) -#define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM) +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM) +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM) +#endif // Timer references by index #define STEP_TIMER_PTR _HAL_TIMER(STEP_TIMER_NUM) diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 322489e193..0829a2ccdc 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -27,7 +27,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" #include "watchdog.h" -#include "timers.h" #ifdef ADAFRUIT_GRAND_CENTRAL_M4 #include "MarlinSerial_AGCM4.h" diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index b4e22d7f1b..37511dc704 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -32,7 +32,6 @@ #include "../shared/servo.h" #include "../shared/servo_private.h" #include "SAMD51.h" -#include "timers.h" #define __TC_GCLK_ID(t) TC##t##_GCLK_ID #define _TC_GCLK_ID(t) __TC_GCLK_ID(t) diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index 4560e2e674..fa2d4d3e68 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -24,7 +24,6 @@ // Includes // -------------------------------------------------------------------------- #include "../../inc/MarlinConfig.h" -#include "timers.h" // -------------------------------------------------------------------------- // Local defines diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index 69793ea58d..392b8946f5 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -32,9 +32,15 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE F_CPU // frequency of timers peripherals -#define STEP_TIMER_NUM 0 // index of timer to use for stepper (also +1 for 32bits counter) -#define PULSE_TIMER_NUM STEP_TIMER_NUM -#define TEMP_TIMER_NUM RTC_TIMER_NUM // index of timer to use for temperature +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM RTC_TIMER_NUM // Timer Index for Temperature +#endif #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -57,16 +63,18 @@ typedef uint32_t hal_timer_t; : (t == TEMP_TIMER_NUM) ? 6 \ : 7 -#define _TC_HANDLER(t) void TC##t##_Handler() -#define TC_HANDLER(t) _TC_HANDLER(t) -#define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM) +#define _TC_HANDLER(t) void TC##t##_Handler() +#define TC_HANDLER(t) _TC_HANDLER(t) +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM) +#endif #if STEP_TIMER_NUM != PULSE_TIMER_NUM - #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM) + #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM) #endif #if TEMP_TIMER_NUM == RTC_TIMER_NUM - #define HAL_TEMP_TIMER_ISR() void RTC_Handler() + #define HAL_TEMP_TIMER_ISR() void RTC_Handler() #else - #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM) + #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM) #endif // -------------------------------------------------------------------------- diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 3319636704..4046f67044 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -119,7 +119,6 @@ #define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.availableForWrite #endif -#include "timers.h" /** * TODO: review this to return 1 for pins that are not analog input diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.cpp b/Marlin/src/HAL/STM32/SoftwareSerial.cpp index 60f355e08e..e77ad7c52d 100644 --- a/Marlin/src/HAL/STM32/SoftwareSerial.cpp +++ b/Marlin/src/HAL/STM32/SoftwareSerial.cpp @@ -36,8 +36,9 @@ // #if defined(PLATFORMIO) && defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#include "../../inc/MarlinConfig.h" + #include "SoftwareSerial.h" -#include "timers.h" #define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge). diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 0871fbc7d7..3796814da9 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -21,8 +21,6 @@ */ #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) -#include "timers.h" - #include "../../inc/MarlinConfig.h" // ------------------------ diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 60d3b3aaf3..d6b333ef9c 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -33,9 +33,15 @@ #define hal_timer_t uint32_t #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit -#define STEP_TIMER_NUM 0 // index of timer to use for stepper -#define TEMP_TIMER_NUM 1 // index of timer to use for temperature -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif #define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz @@ -57,8 +63,13 @@ extern void Step_Handler(HardwareTimer *htim); extern void Temp_Handler(HardwareTimer *htim); -#define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim) -#define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim) + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim) +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim) +#endif // ------------------------ // Public Variables diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index c69d62e125..49769a59d8 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -36,7 +36,6 @@ #include "fastio.h" #include "watchdog.h" -#include "timers.h" #include #include diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index e5aa9f21e7..3812dc1ab5 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -29,7 +29,6 @@ uint8_t ServoCount = 0; #include "Servo.h" -#include "timers.h" //#include "Servo.h" diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp index 720bd37ba4..b3a9ce4f75 100644 --- a/Marlin/src/HAL/STM32F1/timers.cpp +++ b/Marlin/src/HAL/STM32F1/timers.cpp @@ -27,8 +27,6 @@ #ifdef __STM32F1__ #include "../../inc/MarlinConfig.h" -#include "HAL.h" -#include "timers.h" // ------------------------ // Local defines diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index e5733cc563..442b2eacb2 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -61,14 +61,20 @@ typedef uint16_t hal_timer_t; * - Otherwise it uses Timer 8 on boards with STM32_HIGH_DENSITY * or Timer 4 on other boards. */ -#if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8) - #define STEP_TIMER_NUM 4 // For C8/CB boards, use timer 4 -#else - #define STEP_TIMER_NUM 5 // for other boards, five is fine. +#ifndef STEP_TIMER_NUM + #if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8) + #define STEP_TIMER_NUM 4 // For C8/CB boards, use timer 4 + #else + #define STEP_TIMER_NUM 5 // for other boards, five is fine. + #endif +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 2 // Timer Index for Temperature + //#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM #endif -#define TEMP_TIMER_NUM 2 // index of timer to use for temperature -//#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM -#define PULSE_TIMER_NUM STEP_TIMER_NUM #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE) // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM. @@ -111,8 +117,12 @@ timer_dev* get_timer_dev(int number); // TODO change this -#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() -#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() +#endif +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() +#endif extern "C" void tempTC_Handler(); extern "C" void stepTC_Handler(); diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h index 37bb5552ab..aa8575e6a8 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.h +++ b/Marlin/src/HAL/STM32_F4_F7/HAL.h @@ -31,7 +31,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "timers.h" #include "watchdog.h" #include diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp index bdd01bc814..efbb8c73e3 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp @@ -21,8 +21,7 @@ */ #if defined(STM32GENERIC) && defined(STM32F4) -#include "../HAL.h" -#include "timers.h" +#include "../../../inc/MarlinConfig.h" // ------------------------ // Local defines diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h index c52f5ea21c..c16963e264 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h @@ -34,9 +34,15 @@ #define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals -#define STEP_TIMER_NUM 0 // index of timer to use for stepper -#define TEMP_TIMER_NUM 1 // index of timer to use for temperature -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif #define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -59,17 +65,19 @@ // TODO change this #ifdef STM32GENERIC - extern void TC5_Handler(); - extern void TC7_Handler(); - #define HAL_STEP_TIMER_ISR() void TC5_Handler() - #define HAL_TEMP_TIMER_ISR() void TC7_Handler() + #define TC_TIMER_ARGS #else - extern void TC5_Handler(stimer_t *htim); - extern void TC7_Handler(stimer_t *htim); - #define HAL_STEP_TIMER_ISR() void TC5_Handler(stimer_t *htim) - #define HAL_TEMP_TIMER_ISR() void TC7_Handler(stimer_t *htim) + #define TC_TIMER_ARGS stimer_t *htim #endif +extern void TC5_Handler(TC_TIMER_ARGS); +extern void TC7_Handler(TC_TIMER_ARGS); +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() void TC5_Handler(TC_TIMER_ARGS) +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() void TC7_Handler(TC_TIMER_ARGS) +#endif // ------------------------ // Types diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp index 6a9285f3da..b9ba497ab1 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp @@ -21,8 +21,7 @@ */ #if defined(STM32GENERIC) && defined(STM32F7) -#include "../HAL.h" -#include "timers.h" +#include "../../../inc/MarlinConfig.h" // ------------------------ // Local defines diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h index 00428c54f1..6c5e70cde6 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h @@ -34,9 +34,15 @@ #define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals -#define STEP_TIMER_NUM 0 // index of timer to use for stepper -#define TEMP_TIMER_NUM 1 // index of timer to use for temperature -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency #define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz @@ -62,8 +68,12 @@ extern void TC5_Handler(); extern void TC7_Handler(); -#define HAL_STEP_TIMER_ISR() void TC5_Handler() -#define HAL_TEMP_TIMER_ISR() void TC7_Handler() +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() void TC5_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() void TC7_Handler() +#endif // ------------------------ // Types diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 15e9ab71bb..23e4c18571 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -34,7 +34,6 @@ #include "fastio.h" #include "watchdog.h" -#include "timers.h" #include diff --git a/Marlin/src/HAL/TEENSY31_32/timers.cpp b/Marlin/src/HAL/TEENSY31_32/timers.cpp index 92641742f9..b09f8fa6f9 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.cpp +++ b/Marlin/src/HAL/TEENSY31_32/timers.cpp @@ -26,8 +26,7 @@ #ifdef __MK20DX256__ -#include "HAL.h" -#include "timers.h" +#include "../../inc/MarlinConfig.h" /** \brief Instruction Synchronization Barrier Instruction Synchronization Barrier flushes the pipeline in the processor, diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 00f9f0740d..53e6e00eba 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -47,9 +47,15 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE (FTM0_TIMER_RATE) -#define STEP_TIMER_NUM 0 -#define TEMP_TIMER_NUM 1 -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif #define TEMP_TIMER_FREQUENCY 1000 @@ -68,8 +74,12 @@ typedef uint32_t hal_timer_t; #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) -#define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() -#define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() +#endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 7e5be1081c..7aa10abe95 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -34,8 +34,6 @@ #include "fastio.h" #include "watchdog.h" -#include "timers.h" - #include #include diff --git a/Marlin/src/HAL/TEENSY35_36/timers.cpp b/Marlin/src/HAL/TEENSY35_36/timers.cpp index 81e23e4d17..009d06223d 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.cpp +++ b/Marlin/src/HAL/TEENSY35_36/timers.cpp @@ -27,8 +27,7 @@ #if defined(__MK64FX512__) || defined(__MK66FX1M0__) -#include "HAL.h" -#include "timers.h" +#include "../../inc/MarlinConfig.h" /** \brief Instruction Synchronization Barrier Instruction Synchronization Barrier flushes the pipeline in the processor, diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 6dc26a9665..f2f9558675 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -46,9 +46,15 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE (FTM0_TIMER_RATE) -#define STEP_TIMER_NUM 0 -#define TEMP_TIMER_NUM 1 -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif #define TEMP_TIMER_FREQUENCY 1000 @@ -67,8 +73,12 @@ typedef uint32_t hal_timer_t; #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) -#define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() -#define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() +#endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index c1655015e0..90fc110042 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -30,6 +30,7 @@ #include "../HAL/HAL.h" #include "../pins/pins.h" +#include HAL_PATH(../HAL, timers.h) #include HAL_PATH(../HAL, spi_pins.h) #include "Conditionals_post.h" diff --git a/Marlin/src/pins/sam/pins_ARCHIM1.h b/Marlin/src/pins/sam/pins_ARCHIM1.h index 606e024697..a0d7d1b742 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM1.h +++ b/Marlin/src/pins/sam/pins_ARCHIM1.h @@ -46,6 +46,7 @@ // // Timers // +// These are already defined in DUE, so must be undefined first #define STEP_TIMER_NUM 3 #define HAL_STEP_TIMER_ISR() void TC3_Handler() From 544f7202a3d15396ae42063d2507de1e5fde9b55 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 2 Jun 2020 00:06:17 +0000 Subject: [PATCH 0562/1454] [cron] Bump distribution date (2020-06-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6459baf515..e8d6742a28 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-06-01" + #define STRING_DISTRIBUTION_DATE "2020-06-02" #endif /** From 53cb2963dc3091828e6aedc2deec8a123b3634eb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 1 Jun 2020 19:42:56 -0500 Subject: [PATCH 0563/1454] Fix chirp with TOUCH_BUTTONS --- Marlin/src/lcd/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 753f8a5b48..15276fcb43 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -772,7 +772,7 @@ void MarlinUI::update() { if (!wait_for_unclick) { next_button_update_ms += 250; // Longer delay on first press wait_for_unclick = true; // Avoid Back/Select click while repeating - TERN_(HAS_BUZZER, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); + chirp(); } } } From 71195961701578d91bb348d71f5adcaa028ae9e9 Mon Sep 17 00:00:00 2001 From: Mark Scammacca Date: Mon, 1 Jun 2020 22:19:10 -0500 Subject: [PATCH 0564/1454] G-code line number for each serial port (for TFTs) (#18165) --- Marlin/src/gcode/host/M110.cpp | 5 ++++- Marlin/src/gcode/queue.cpp | 17 +++++++++-------- Marlin/src/gcode/queue.h | 13 +++++++++++-- 3 files changed, 24 insertions(+), 11 deletions(-) diff --git a/Marlin/src/gcode/host/M110.cpp b/Marlin/src/gcode/host/M110.cpp index f7b6dfd4f4..126063116a 100644 --- a/Marlin/src/gcode/host/M110.cpp +++ b/Marlin/src/gcode/host/M110.cpp @@ -27,5 +27,8 @@ * M110: Set Current Line Number */ void GcodeSuite::M110() { - if (parser.seenval('N')) queue.last_N = parser.value_long(); + + if (parser.seenval('N')) + queue.last_N[queue.command_port()] = parser.value_long(); + } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index b98ef10992..a4a4993556 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -52,7 +52,7 @@ GCodeQueue queue; * sending commands to Marlin, and lines will be checked for sequentiality. * M110 N sets the current line number. */ -long gcode_N, GCodeQueue::last_N; +long GCodeQueue::last_N[NUM_SERIAL]; /** * GCode Command Queue @@ -277,7 +277,7 @@ void GCodeQueue::enqueue_now_P(PGM_P const pgcode) { */ void GCodeQueue::ok_to_send() { #if NUM_SERIAL > 1 - const int16_t pn = port[index_r]; + const int16_t pn = command_port(); if (pn < 0) return; PORT_REDIRECT(pn); // Reply to the serial port that sent the command #endif @@ -302,14 +302,15 @@ void GCodeQueue::ok_to_send() { * indicate that a command needs to be re-sent. */ void GCodeQueue::flush_and_request_resend() { + const int16_t pn = command_port(); #if NUM_SERIAL > 1 - const int16_t pn = port[index_r]; if (pn < 0) return; PORT_REDIRECT(pn); // Reply to the serial port that sent the command #endif SERIAL_FLUSH(); SERIAL_ECHOPGM(STR_RESEND); - SERIAL_ECHOLN(last_N + 1); + + SERIAL_ECHOLN(last_N[pn] + 1); ok_to_send(); } @@ -336,7 +337,7 @@ void GCodeQueue::gcode_line_error(PGM_P const err, const int8_t pn) { PORT_REDIRECT(pn); // Reply to the serial port that sent the command SERIAL_ERROR_START(); serialprintPGM(err); - SERIAL_ECHOLN(last_N); + SERIAL_ECHOLN(last_N[pn]); while (read_serial(pn) != -1); // Clear out the RX buffer flush_and_request_resend(); serial_count[pn] = 0; @@ -475,9 +476,9 @@ void GCodeQueue::get_serial_commands() { if (n2pos) npos = n2pos; } - gcode_N = strtol(npos + 1, nullptr, 10); + const long gcode_N = strtol(npos + 1, nullptr, 10); - if (gcode_N != last_N + 1 && !M110) + if (gcode_N != last_N[i] + 1 && !M110) return gcode_line_error(PSTR(STR_ERR_LINE_NO), i); char *apos = strrchr(command, '*'); @@ -490,7 +491,7 @@ void GCodeQueue::get_serial_commands() { else return gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), i); - last_N = gcode_N; + last_N[i] = gcode_N; } #if ENABLED(SDSUPPORT) // Pronterface "M29" and "M29 " has no line number diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 053d143e76..6c14d7d3db 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -35,7 +35,8 @@ public: * commands to Marlin, and lines will be checked for sequentiality. * M110 N sets the current line number. */ - static long last_N; + + static long last_N[NUM_SERIAL]; /** * GCode Command Queue @@ -51,13 +52,21 @@ public: static char command_buffer[BUFSIZE][MAX_CMD_SIZE]; - /* + /** * The port that the command was received on */ #if NUM_SERIAL > 1 static int16_t port[BUFSIZE]; #endif + static int16_t command_port() { + return (0 + #if NUM_SERIAL > 1 + + port[index_r] + #endif + ); + } + GCodeQueue(); /** From ad08722d0de51e3bda05985416800818e7f0d310 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 1 Jun 2020 20:40:51 -0700 Subject: [PATCH 0565/1454] Chirp followup 2 (#18176) Co-authored-by: Scott Lahteine --- Marlin/src/inc/Conditionals_post.h | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 57295f84b9..97f4d1eb88 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2352,6 +2352,13 @@ /** * Buzzer/Speaker */ +#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #define HAS_BUZZER 1 + #if DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #define USE_BEEPER 1 + #endif +#endif + #if ENABLED(LCD_USE_I2C_BUZZER) #ifndef LCD_FEEDBACK_FREQUENCY_HZ #define LCD_FEEDBACK_FREQUENCY_HZ 1000 @@ -2368,14 +2375,8 @@ #endif #endif -#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) - #define HAS_BUZZER 1 - #if LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ - #define HAS_CHIRP 1 - #endif -#endif -#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) - #define USE_BEEPER 1 +#if HAS_BUZZER && LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ + #define HAS_CHIRP 1 #endif /** From c9a260ee12c9cc6a877a9e1155ddc8c619e4b7a4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 31 May 2020 02:12:29 -0500 Subject: [PATCH 0566/1454] MEEB cleanup, whitespace Followup to #18138 --- .github/workflows/test-builds.yml | 1 + Marlin/src/pins/pins.h | 2 +- .../scripts/STM32F103RC_MEEB_3DP.py | 6 ++--- .../STM32F103RC_MEEB_3DP_create_variant.py | 4 ++-- .../PlatformIO/variants/MEEB_3DP/board.cpp | 22 +++++++++---------- .../variants/MEEB_3DP/ld/stm32f103rb.ld | 2 +- .../variants/MEEB_3DP/ld/stm32f103rc.ld | 2 +- .../variants/MEEB_3DP/ld/stm32f103re.ld | 2 +- .../variants/MEEB_3DP/wirish/boards_setup.cpp | 14 ++++++------ ..._meeb_3dp-tests => STM32F103RC_meeb-tests} | 0 platformio.ini | 2 +- 11 files changed, 28 insertions(+), 29 deletions(-) rename buildroot/share/tests/{STM32F103RC_cc_meeb_3dp-tests => STM32F103RC_meeb-tests} (100%) diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 22ca222b91..1e48822dcd 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -49,6 +49,7 @@ jobs: - STM32F103RE_btt - STM32F103RE_btt_USB - STM32F103RC_fysetc + - STM32F103RC_meeb - jgaurora_a5s_a1 - STM32F103VE_longer - STM32F407VE_black diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b8f01e5626..6c19129f93 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -535,7 +535,7 @@ #elif MB(MKS_ROBIN_E3) #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 #elif MB(CCROBOT_MEEB_3DP) - #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_cc_meeb_3dp + #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_meeb // // ARM Cortex-M4F diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py index 9176ab3278..547d80ace5 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py @@ -13,7 +13,7 @@ print(projenv) config = configparser.ConfigParser() config.read("platformio.ini") -#com_port = config.get("env:STM32F103RC_cc_meeb_3dp", "upload_port") +#com_port = config.get("env:STM32F103RC_meeb", "upload_port") #print('Use the {0:s} to reboot the board to dfu mode.'.format(com_port)) # @@ -48,7 +48,7 @@ for define in env['CPPDEFINES']: if define[0] == "STM32_FLASH_SIZE": flash_size = define[1] -print('Use the {0:s} address as the marlin app entry point.'.format(vect_tab_addr)) +print('Use the {0:s} address as the marlin app entry point.'.format(vect_tab_addr)) print('Use the {0:d}KB flash version of stm32f103rct6 chip.'.format(flash_size)) custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/STM32F103RC_MEEB_3DP.ld") @@ -57,5 +57,3 @@ for i, flag in enumerate(env["LINKFLAGS"]): env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script elif flag == "-T": env["LINKFLAGS"][i + 1] = custom_ld_script - - diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py index e4f9b672d1..4849f59ceb 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py @@ -27,8 +27,8 @@ assert os.path.isdir(source_dir) if os.path.isdir(variant_dir): shutil.rmtree(variant_dir) - + if not os.path.isdir(variant_dir): os.mkdir(variant_dir) -copytree(source_dir, variant_dir) \ No newline at end of file +copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp b/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp index 5b602de49a..9a678c01e7 100644 --- a/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/board.cpp @@ -73,19 +73,19 @@ void boardInit(void) { extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { /* - gpio_dev *gpio_device; GPIO device + gpio_dev *gpio_device; GPIO device timer_dev *timer_device; Pin's timer device, if any. - const adc_dev *adc_device; ADC device, if any. - uint8 gpio_bit; Pin's GPIO port bit. - uint8 timer_channel; Timer channel, or 0 if none. - uint8 adc_channel; Pin ADC channel, or ADCx if none. + const adc_dev *adc_device; ADC device, if any. + uint8 gpio_bit; Pin's GPIO port bit. + uint8 timer_channel; Timer channel, or 0 if none. + uint8 adc_channel; Pin ADC channel, or ADCx if none. */ {&gpioa, &timer2, &adc1, 0, 1, 0}, /* PA0 */ {&gpioa, &timer2, &adc1, 1, 2, 1}, /* PA1 */ {&gpioa, &timer2, &adc1, 2, 3, 2}, /* PA2 */ {&gpioa, &timer2, &adc1, 3, 4, 3}, /* PA3 */ - {&gpioa, NULL, &adc1, 4, 0, 4}, /* PA4 */ + {&gpioa, NULL, &adc1, 4, 0, 4}, /* PA4 */ {&gpioa, NULL, &adc1, 5, 0, 5}, /* PA5 */ {&gpioa, &timer3, &adc1, 6, 1, 6}, /* PA6 */ {&gpioa, &timer3, &adc1, 7, 2, 7}, /* PA7 */ @@ -93,14 +93,14 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {&gpioa, &timer1, NULL, 9, 2, ADCx}, /* PA9 */ {&gpioa, &timer1, NULL, 10, 3, ADCx}, /* PA10 */ {&gpioa, NULL, NULL, 11, 0, ADCx}, /* PA11 */ - {&gpioa, NULL, NULL, 12, 0, ADCx}, /* PA12 */ + {&gpioa, NULL, NULL, 12, 0, ADCx}, /* PA12 */ {&gpioa, NULL, NULL, 13, 0, ADCx}, /* PA13 */ {&gpioa, NULL, NULL, 14, 0, ADCx}, /* PA14 */ {&gpioa, NULL, NULL, 15, 0, ADCx}, /* PA15 */ - + {&gpiob, &timer3, &adc1, 0, 3, 8}, /* PB0 */ {&gpiob, &timer3, &adc1, 1, 4, 9}, /* PB1 */ - {&gpiob, NULL, NULL, 2, 0, ADCx}, /* PB2 */ + {&gpiob, NULL, NULL, 2, 0, ADCx}, /* PB2 */ {&gpiob, NULL, NULL, 3, 0, ADCx}, /* PB3 */ {&gpiob, NULL, NULL, 4, 0, ADCx}, /* PB4 */ {&gpiob, NULL, NULL, 5, 0, ADCx}, /* PB5 */ @@ -122,13 +122,13 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {&gpioc, NULL, &adc1, 3, 0, 13}, /* PC3 */ {&gpioc, NULL, &adc1, 4, 0, 14}, /* PC4 */ {&gpioc, NULL, &adc1, 5, 0, 15}, /* PC5 */ - {&gpioc, &timer8, NULL, 6, 1, ADCx}, /* PC6 */ + {&gpioc, &timer8, NULL, 6, 1, ADCx}, /* PC6 */ {&gpioc, &timer8, NULL, 7, 2, ADCx}, /* PC7 */ {&gpioc, &timer8, NULL, 8, 3, ADCx}, /* PC8 */ {&gpioc, &timer8, NULL, 9, 4, ADCx}, /* PC9 */ {&gpioc, NULL, NULL, 10, 0, ADCx}, /* PC10 UART4_TX/SDIO_D2 */ {&gpioc, NULL, NULL, 11, 0, ADCx}, /* PC11 UART4_RX/SDIO_D3 */ - {&gpioc, NULL, NULL, 12, 0, ADCx}, /* PC12 UART5_TX/SDIO_CK */ + {&gpioc, NULL, NULL, 12, 0, ADCx}, /* PC12 UART5_TX/SDIO_CK */ {&gpioc, NULL, NULL, 13, 0, ADCx}, /* PC13 TAMPER-RTC */ {&gpioc, NULL, NULL, 14, 0, ADCx}, /* PC14 OSC32_IN */ {&gpioc, NULL, NULL, 15, 0, ADCx}, /* PC15 OSC32_OUT */ diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld index 9c0d19b716..094f2d2928 100644 --- a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rb.ld @@ -1,5 +1,5 @@ /* - * Linker script for Generic STM32F103RB boards. + * Linker script for Generic STM32F103RB boards. */ MEMORY { diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld index 016d59d00d..c890d69f6d 100644 --- a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103rc.ld @@ -1,5 +1,5 @@ /* - * Linker script for Generic STM32F103RC boards. + * Linker script for Generic STM32F103RC boards. */ MEMORY { diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld index 52abb5ad09..9f74fd5292 100644 --- a/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/ld/stm32f103re.ld @@ -1,5 +1,5 @@ /* - * Linker script for Generic STM32F103RE boards. + * Linker script for Generic STM32F103RE boards. */ MEMORY { diff --git a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp index d4e95925ac..3e534dc3c9 100644 --- a/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp +++ b/buildroot/share/PlatformIO/variants/MEEB_3DP/wirish/boards_setup.cpp @@ -72,8 +72,8 @@ namespace wirish { #if F_CPU == 72000000 rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1_5); #elif F_CPU == 48000000 - rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1); - #endif + rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1); + #endif } __weak void board_setup_gpio(void) { @@ -81,16 +81,16 @@ namespace wirish { } __weak void board_setup_usb(void) { -#ifdef SERIAL_USB - -#ifdef GENERIC_BOOTLOADER +#ifdef SERIAL_USB + +#ifdef GENERIC_BOOTLOADER //Reset the USB interface on generic boards - developed by Victor PV gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_OUTPUT_PP); gpio_write_bit(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit,0); - + for(volatile unsigned int i=0;i<512;i++);// Only small delay seems to be needed, and USB pins will get configured in Serial.begin gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_INPUT_FLOATING); -#endif +#endif Serial.begin();// Roger Clark. Changed SerialUSB to Serial for Arduino sketch compatibility #endif diff --git a/buildroot/share/tests/STM32F103RC_cc_meeb_3dp-tests b/buildroot/share/tests/STM32F103RC_meeb-tests similarity index 100% rename from buildroot/share/tests/STM32F103RC_cc_meeb_3dp-tests rename to buildroot/share/tests/STM32F103RC_meeb-tests diff --git a/platformio.ini b/platformio.ini index fa27fb9a9a..a8948024b8 100644 --- a/platformio.ini +++ b/platformio.ini @@ -282,7 +282,7 @@ monitor_speed = 115200 # # MEEB_3DP (STM32F103RCT6 with 512K) # -[env:STM32F103RC_cc_meeb_3dp] +[env:STM32F103RC_meeb] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = MEEB_3DP From a1f3d2f3cd9bf8bb4da16da0e55cdb5ff264a15d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 31 May 2020 01:03:28 -0500 Subject: [PATCH 0567/1454] Move set_all_z_lock to Stepper --- Marlin/src/gcode/calibrate/G34_M422.cpp | 25 ++----------------------- Marlin/src/module/motion.cpp | 8 ++++---- Marlin/src/module/stepper.h | 12 +++++++++++- 3 files changed, 17 insertions(+), 28 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index f5addd9cd6..0961cce59c 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -47,17 +47,6 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" -inline void set_all_z_lock(const bool lock) { - stepper.set_z_lock(lock); - stepper.set_z2_lock(lock); - #if NUM_Z_STEPPER_DRIVERS >= 3 - stepper.set_z3_lock(lock); - #if NUM_Z_STEPPER_DRIVERS >= 4 - stepper.set_z4_lock(lock); - #endif - #endif -} - /** * G34: Z-Stepper automatic alignment * @@ -318,17 +307,7 @@ void GcodeSuite::G34() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " corrected by ", z_align_move); // Lock all steppers except one - set_all_z_lock(true); - switch (zstepper) { - case 0: stepper.set_z_lock(false); break; - case 1: stepper.set_z2_lock(false); break; - #if NUM_Z_STEPPER_DRIVERS >= 3 - case 2: stepper.set_z3_lock(false); break; - #endif - #if NUM_Z_STEPPER_DRIVERS == 4 - case 3: stepper.set_z4_lock(false); break; - #endif - } + stepper.set_all_z_lock(true, zstepper); #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) // Decreasing accuracy was detected so move was inverted. @@ -342,7 +321,7 @@ void GcodeSuite::G34() { } // for (zstepper) // Back to normal stepper operations - set_all_z_lock(false); + stepper.set_all_z_lock(false); stepper.set_separate_multi_axis(false); if (err_break) break; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 09f0f390c5..727bb15271 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1644,9 +1644,9 @@ void homeaxis(const AxisEnum axis) { const float adj = ABS(endstops.z2_endstop_adj); if (adj) { - if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true); + if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z1_lock(true); else stepper.set_z2_lock(true); do_homing_move(axis, pos_dir ? -adj : adj); - stepper.set_z_lock(false); + stepper.set_z1_lock(false); stepper.set_z2_lock(false); } @@ -1657,7 +1657,7 @@ void homeaxis(const AxisEnum axis) { typedef void (*adjustFunc_t)(const bool); adjustFunc_t lock[] = { - stepper.set_z_lock, stepper.set_z2_lock, stepper.set_z3_lock + stepper.set_z1_lock, stepper.set_z2_lock, stepper.set_z3_lock #if NUM_Z_STEPPER_DRIVERS >= 4 , stepper.set_z4_lock #endif @@ -1725,7 +1725,7 @@ void homeaxis(const AxisEnum axis) { do_homing_move(axis, adj[0] - adj[1]); } - stepper.set_z_lock(false); + stepper.set_z1_lock(false); stepper.set_z2_lock(false); stepper.set_z3_lock(false); #if NUM_Z_STEPPER_DRIVERS >= 4 diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 38af36db51..bc35f55ff2 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -484,7 +484,7 @@ class Stepper { FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; } #endif #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) - FORCE_INLINE static void set_z_lock(const bool state) { locked_Z_motor = state; } + FORCE_INLINE static void set_z1_lock(const bool state) { locked_Z_motor = state; } FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; } #if NUM_Z_STEPPER_DRIVERS >= 3 FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; } @@ -492,6 +492,16 @@ class Stepper { FORCE_INLINE static void set_z4_lock(const bool state) { locked_Z4_motor = state; } #endif #endif + static inline void set_all_z_lock(const bool lock, const int8_t except=-1) { + set_z1_lock(lock ^ (except == 0)); + set_z2_lock(lock ^ (except == 1)); + #if NUM_Z_STEPPER_DRIVERS >= 3 + set_z3_lock(lock ^ (except == 2)); + #if NUM_Z_STEPPER_DRIVERS >= 4 + set_z4_lock(lock ^ (except == 3)); + #endif + #endif + } #endif #if ENABLED(BABYSTEPPING) From 142e65192db2ab4c275a79ffa00e70e3069cabe1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 3 Jun 2020 00:06:23 +0000 Subject: [PATCH 0568/1454] [cron] Bump distribution date (2020-06-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e8d6742a28..ae8e5cf24f 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-06-02" + #define STRING_DISTRIBUTION_DATE "2020-06-03" #endif /** From 5f9624f70b78fecd7f2f27318b01578bcd038a06 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 2 Jun 2020 19:12:08 -0500 Subject: [PATCH 0569/1454] Ensure XY known for Z safe homing Addressing #18143 --- Marlin/src/gcode/calibrate/G28.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index bd847658ca..3f41f076b5 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -294,7 +294,10 @@ void GcodeSuite::G28() { #else // NOT DELTA - const bool homeX = parser.seen('X'), homeY = parser.seen('Y'), homeZ = parser.seen('Z'), + const bool homeZ = parser.seen('Z'), + needX = homeZ && TERN0(Z_SAFE_HOMING, axes_need_homing(_BV(X_AXIS))), + needY = homeZ && TERN0(Z_SAFE_HOMING, axes_need_homing(_BV(Y_AXIS))), + homeX = needX || parser.seen('X'), homeY = needY || parser.seen('Y'), home_all = homeX == homeY && homeX == homeZ, // All or None doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; From a0b27e67022859bf2d9cad5be8fdc02301e50d1a Mon Sep 17 00:00:00 2001 From: XDA-Bam <1209896+XDA-Bam@users.noreply.github.com> Date: Wed, 3 Jun 2020 02:30:43 +0200 Subject: [PATCH 0570/1454] Fix JD LUT math & bugs (#18175) --- Marlin/src/module/planner.cpp | 31 ++++++++++++++++--------------- 1 file changed, 16 insertions(+), 15 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 38442d7b96..5602495b47 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2319,16 +2319,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move, /** * // Generate the JD Lookup Table - * constexpr float c = 1.00751317f; // Correction factor to center error around 0 + * constexpr float c = 1.00751495f; // Correction factor to center error around 0 * for (int i = 0; i < jd_lut_count - 1; ++i) { * const float x0 = (sq(i) - 1) / sq(i), - * y0 = acos(x0) * (i ? c : 1), - * x1 = 0.5 * x0 + 0.5, - * y1 = acos(x1) * c; + * y0 = acos(x0) * (i == 0 ? 1 : c), + * x1 = i < jd_lut_count - 1 ? 0.5 * x0 + 0.5 : 0.999999f, + * y1 = acos(x1) * (i < jd_lut_count - 1 ? c : 1); * jd_lut_k[i] = (y0 - y1) / (x0 - x1); * jd_lut_b[i] = (y1 * x0 - y0 * x1) / (x0 - x1); * } - * jd_lut_k[jd_lut_count - 1] = jd_lut_b[jd_lut_count - 1] = 0; * * // Compute correction factor (Set c to 1.0f first!) * float min = INFINITY, max = -min; @@ -2341,22 +2340,24 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * } * fprintf(stderr, "%.9gf, ", (min + max) / 2); */ - static constexpr int16_t jd_lut_count = 15; - static constexpr uint16_t jd_lut_tll = 1 << jd_lut_count; - static constexpr int16_t jd_lut_tll0 = __builtin_clz(jd_lut_tll) + 1; // i.e., 16 - jd_lut_count + static constexpr int16_t jd_lut_count = 16; + static constexpr uint16_t jd_lut_tll = _BV(jd_lut_count - 1); + static constexpr int16_t jd_lut_tll0 = __builtin_clz(jd_lut_tll) + 1; // i.e., 16 - jd_lut_count + 1 static constexpr float jd_lut_k[jd_lut_count] PROGMEM = { - -1.03146219f, -1.30760407f, -1.75205469f, -2.41705418f, -3.37768555f, - -4.74888229f, -6.69648552f, -9.45659828f, -13.3640289f, -18.8927879f, - -26.7136307f, -37.7754059f, -53.4200745f, -75.5457306f, 0.0f }; + -1.03145837f, -1.30760646f, -1.75205851f, -2.41705704f, + -3.37769222f, -4.74888992f, -6.69649887f, -9.45661736f, + -13.3640480f, -18.8928222f, -26.7136841f, -37.7754593f, + -53.4201813f, -75.5458374f, -106.836761f, -218.532821f }; static constexpr float jd_lut_b[jd_lut_count] PROGMEM = { - 1.57079637f, 1.70886743f, 2.04220533f, 2.62408018f, 3.52467203f, - 4.85301876f, 6.77019119f, 9.50873947f, 13.4009094f, 18.9188652f, - 26.7320709f, 37.7884521f, 53.4292908f, 75.5522461f, 0.0f }; + 1.57079637f, 1.70887053f, 2.04220939f, 2.62408352f, + 3.52467871f, 4.85302639f, 6.77020454f, 9.50875854f, + 13.4009285f, 18.9188995f, 26.7321243f, 37.7885055f, + 53.4293975f, 75.5523529f, 106.841369f, 218.534011f }; const float neg = junction_cos_theta < 0 ? -1 : 1, t = neg * junction_cos_theta; - const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(uint16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; + const int16_t idx = (t < 0.00000003f) ? 0 : __builtin_clz(uint16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0; float junction_theta = t * pgm_read_float(&jd_lut_k[idx]) + pgm_read_float(&jd_lut_b[idx]); if (neg > 0) junction_theta = RADIANS(180) - junction_theta; // acos(-t) From ce62209bce9a1bd64cda1e72d5982a4ff0b593a2 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 3 Jun 2020 13:41:50 +1200 Subject: [PATCH 0571/1454] Probe margin. Bump config version (#18140) Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 4 +-- Marlin/Configuration_adv.h | 14 +++++---- Marlin/src/feature/z_stepper_align.cpp | 8 +++--- Marlin/src/inc/Conditionals_post.h | 36 +++++++++++------------ Marlin/src/inc/SanityCheck.h | 40 +++++++++++++++++++------- Marlin/src/inc/Version.h | 2 +- Marlin/src/module/delta.cpp | 2 +- Marlin/src/module/probe.h | 14 ++++----- 8 files changed, 70 insertions(+), 50 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index cb5ae06617..da61c00c16 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -36,7 +36,7 @@ * Advanced settings can be found in Configuration_adv.h * */ -#define CONFIGURATION_H_VERSION 020005 +#define CONFIGURATION_H_VERSION 020006 //=========================================================================== //============================= Getting Started ============================= @@ -976,7 +976,7 @@ // Most probes should stay away from the edges of the bed, but // with NOZZLE_AS_PROBE this can be negative for a wider probing area. -#define MIN_PROBE_EDGE 10 +#define PROBING_MARGIN 10 // X and Y axis travel speed (mm/m) between probes #define XY_PROBE_SPEED 8000 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ec6cb27ec4..e71f4c467c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -31,7 +31,7 @@ * Basic settings can be found in Configuration.h * */ -#define CONFIGURATION_ADV_H_VERSION 020005 +#define CONFIGURATION_ADV_H_VERSION 020006 // @section temperature @@ -1589,7 +1589,9 @@ #endif /** - * Override MIN_PROBE_EDGE for each side of the build plate + * Probing Margins + * + * Override PROBING_MARGIN for each side of the build plate * Useful to get probe points to exact positions on targets or * to allow leveling to avoid plate clamps on only specific * sides of the bed. With NOZZLE_AS_PROBE negative values are @@ -1606,10 +1608,10 @@ * the probe to be unable to reach any points. */ #if PROBE_SELECTED && !IS_KINEMATIC - //#define MIN_PROBE_EDGE_LEFT MIN_PROBE_EDGE - //#define MIN_PROBE_EDGE_RIGHT MIN_PROBE_EDGE - //#define MIN_PROBE_EDGE_FRONT MIN_PROBE_EDGE - //#define MIN_PROBE_EDGE_BACK MIN_PROBE_EDGE + //#define PROBING_MARGIN_LEFT PROBING_MARGIN + //#define PROBING_MARGIN_RIGHT PROBING_MARGIN + //#define PROBING_MARGIN_FRONT PROBING_MARGIN + //#define PROBING_MARGIN_BACK PROBING_MARGIN #endif #if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) diff --git a/Marlin/src/feature/z_stepper_align.cpp b/Marlin/src/feature/z_stepper_align.cpp index 6fccff7cc9..3614d60371 100644 --- a/Marlin/src/feature/z_stepper_align.cpp +++ b/Marlin/src/feature/z_stepper_align.cpp @@ -56,10 +56,10 @@ void ZStepperAlign::reset_to_default() { constexpr xyz_pos_t dpo = NOZZLE_TO_PROBE_OFFSET; - #define LTEST(N) (xy_init[N].x >= _MAX(X_MIN_BED + MIN_PROBE_EDGE_LEFT, X_MIN_POS + dpo.x) - 0.00001f) - #define RTEST(N) (xy_init[N].x <= _MIN(X_MAX_BED - MIN_PROBE_EDGE_RIGHT, X_MAX_POS + dpo.x) + 0.00001f) - #define FTEST(N) (xy_init[N].y >= _MAX(Y_MIN_BED + MIN_PROBE_EDGE_FRONT, Y_MIN_POS + dpo.y) - 0.00001f) - #define BTEST(N) (xy_init[N].y <= _MIN(Y_MAX_BED - MIN_PROBE_EDGE_BACK, Y_MAX_POS + dpo.y) + 0.00001f) + #define LTEST(N) (xy_init[N].x >= _MAX(X_MIN_BED + PROBING_MARGIN_LEFT, X_MIN_POS + dpo.x) - 0.00001f) + #define RTEST(N) (xy_init[N].x <= _MIN(X_MAX_BED - PROBING_MARGIN_RIGHT, X_MAX_POS + dpo.x) + 0.00001f) + #define FTEST(N) (xy_init[N].y >= _MAX(Y_MIN_BED + PROBING_MARGIN_FRONT, Y_MIN_POS + dpo.y) - 0.00001f) + #define BTEST(N) (xy_init[N].y <= _MIN(Y_MAX_BED - PROBING_MARGIN_BACK, Y_MAX_POS + dpo.y) + 0.00001f) static_assert(LTEST(0) && RTEST(0), "The 1st Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); static_assert(FTEST(0) && BTEST(0), "The 1st Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 97f4d1eb88..edc981520d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2251,31 +2251,31 @@ * Bed Probing bounds */ -#ifndef MIN_PROBE_EDGE - #define MIN_PROBE_EDGE 0 +#ifndef PROBING_MARGIN + #define PROBING_MARGIN 0 #endif #if IS_KINEMATIC - #undef MIN_PROBE_EDGE_LEFT - #undef MIN_PROBE_EDGE_RIGHT - #undef MIN_PROBE_EDGE_FRONT - #undef MIN_PROBE_EDGE_BACK - #define MIN_PROBE_EDGE_LEFT 0 - #define MIN_PROBE_EDGE_RIGHT 0 - #define MIN_PROBE_EDGE_FRONT 0 - #define MIN_PROBE_EDGE_BACK 0 + #undef PROBING_MARGIN_LEFT + #undef PROBING_MARGIN_RIGHT + #undef PROBING_MARGIN_FRONT + #undef PROBING_MARGIN_BACK + #define PROBING_MARGIN_LEFT 0 + #define PROBING_MARGIN_RIGHT 0 + #define PROBING_MARGIN_FRONT 0 + #define PROBING_MARGIN_BACK 0 #else - #ifndef MIN_PROBE_EDGE_LEFT - #define MIN_PROBE_EDGE_LEFT MIN_PROBE_EDGE + #ifndef PROBING_MARGIN_LEFT + #define PROBING_MARGIN_LEFT PROBING_MARGIN #endif - #ifndef MIN_PROBE_EDGE_RIGHT - #define MIN_PROBE_EDGE_RIGHT MIN_PROBE_EDGE + #ifndef PROBING_MARGIN_RIGHT + #define PROBING_MARGIN_RIGHT PROBING_MARGIN #endif - #ifndef MIN_PROBE_EDGE_FRONT - #define MIN_PROBE_EDGE_FRONT MIN_PROBE_EDGE + #ifndef PROBING_MARGIN_FRONT + #define PROBING_MARGIN_FRONT PROBING_MARGIN #endif - #ifndef MIN_PROBE_EDGE_BACK - #define MIN_PROBE_EDGE_BACK MIN_PROBE_EDGE + #ifndef PROBING_MARGIN_BACK + #define PROBING_MARGIN_BACK PROBING_MARGIN #endif #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 905bcc0bd7..e7d7739117 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -283,9 +283,9 @@ #elif defined(NEOPIXEL_RGBW_LED) #error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED. Please update your configuration." #elif ENABLED(DELTA) && defined(DELTA_PROBEABLE_RADIUS) - #error "Remove DELTA_PROBEABLE_RADIUS and use MIN_PROBE_EDGE to inset the probe area instead." + #error "Remove DELTA_PROBEABLE_RADIUS and use PROBING_MARGIN to inset the probe area instead." #elif ENABLED(DELTA) && defined(DELTA_CALIBRATION_RADIUS) - #error "Remove DELTA_CALIBRATION_RADIUS and use MIN_PROBE_EDGE to inset the probe area instead." + #error "Remove DELTA_CALIBRATION_RADIUS and use PROBING_MARGIN to inset the probe area instead." #elif defined(UBL_MESH_INSET) #error "UBL_MESH_INSET is now just MESH_INSET. Please update your configuration." #elif defined(UBL_MESH_MIN_X) || defined(UBL_MESH_MIN_Y) || defined(UBL_MESH_MAX_X) || defined(UBL_MESH_MAX_Y) @@ -294,14 +294,24 @@ #error "ABL_PROBE_PT_[123]_[XY] is no longer required. Please remove it from Configuration.h." #elif defined(UBL_PROBE_PT_1_X) || defined(UBL_PROBE_PT_1_Y) || defined(UBL_PROBE_PT_2_X) || defined(UBL_PROBE_PT_2_Y) || defined(UBL_PROBE_PT_3_X) || defined(UBL_PROBE_PT_3_Y) #error "UBL_PROBE_PT_[123]_[XY] is no longer required. Please remove it from Configuration.h." +#elif defined(MIN_PROBE_EDGE) + #error "MIN_PROBE_EDGE is now called PROBING_MARGIN. Please update your configuration." +#elif defined(MIN_PROBE_EDGE_LEFT) + #error "MIN_PROBE_EDGE_LEFT is now called PROBING_MARGIN_LEFT. Please update your configuration." +#elif defined(MIN_PROBE_EDGE_RIGHT) + #error "MIN_PROBE_EDGE_RIGHT is now called PROBING_MARGIN_RIGHT. Please update your configuration." +#elif defined(MIN_PROBE_EDGE_FRONT) + #error "MIN_PROBE_EDGE_FRONT is now called PROBING_MARGIN_FRONT. Please update your configuration." +#elif defined(MIN_PROBE_EDGE_BACK) + #error "MIN_PROBE_EDGE_BACK is now called PROBING_MARGIN_BACK. Please update your configuration." #elif defined(LEFT_PROBE_BED_POSITION) - #error "LEFT_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_LEFT instead." + #error "LEFT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_LEFT instead." #elif defined(RIGHT_PROBE_BED_POSITION) - #error "RIGHT_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_RIGHT instead." + #error "RIGHT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_RIGHT instead." #elif defined(FRONT_PROBE_BED_POSITION) - #error "FRONT_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_FRONT instead." + #error "FRONT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_FRONT instead." #elif defined(BACK_PROBE_BED_POSITION) - #error "BACK_PROBE_BED_POSITION is obsolete. Set a margin with MIN_PROBE_EDGE or MIN_PROBE_EDGE_BACK instead." + #error "BACK_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_BACK instead." #elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY) #error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY. Please update your configuration." #elif defined(BABYSTEP_ZPROBE_GFX_REVERSE) @@ -1263,13 +1273,21 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if DISABLED(NOZZLE_AS_PROBE) - static_assert(MIN_PROBE_EDGE >= 0, "MIN_PROBE_EDGE must be >= 0."); - static_assert(MIN_PROBE_EDGE_BACK >= 0, "MIN_PROBE_EDGE_BACK must be >= 0."); - static_assert(MIN_PROBE_EDGE_FRONT >= 0, "MIN_PROBE_EDGE_FRONT must be >= 0."); - static_assert(MIN_PROBE_EDGE_LEFT >= 0, "MIN_PROBE_EDGE_LEFT must be >= 0."); - static_assert(MIN_PROBE_EDGE_RIGHT >= 0, "MIN_PROBE_EDGE_RIGHT must be >= 0."); + static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0."); + static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0."); + static_assert(PROBING_MARGIN_FRONT >= 0, "PROBING_MARGIN_FRONT must be >= 0."); + static_assert(PROBING_MARGIN_LEFT >= 0, "PROBING_MARGIN_LEFT must be >= 0."); + static_assert(PROBING_MARGIN_RIGHT >= 0, "PROBING_MARGIN_RIGHT must be >= 0."); #endif + #define _MARGIN(A) TERN(IS_SCARA, SCARA_PRINTABLE_RADIUS, TERN(DELTA, DELTA_PRINTABLE_RADIUS, A##_CENTER)) + static_assert(PROBING_MARGIN < _MARGIN(X), "PROBING_MARGIN is too large."); + static_assert(PROBING_MARGIN_BACK < _MARGIN(Y), "PROBING_MARGIN_BACK is too large."); + static_assert(PROBING_MARGIN_FRONT < _MARGIN(Y), "PROBING_MARGIN_FRONT is too large."); + static_assert(PROBING_MARGIN_LEFT < _MARGIN(X), "PROBING_MARGIN_LEFT is too large."); + static_assert(PROBING_MARGIN_RIGHT < _MARGIN(X), "PROBING_MARGIN_RIGHT is too large."); + #undef _MARGIN + /** * Make sure Z raise values are set */ diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ae8e5cf24f..4a3af243f0 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 020005 +#define MARLIN_HEX_VERSION 020006 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index a91a8e8545..56b9e0a11e 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -95,7 +95,7 @@ void recalc_delta_settings() { float delta_calibration_radius() { return calibration_radius_factor * ( #if HAS_BED_PROBE - FLOOR((DELTA_PRINTABLE_RADIUS) - _MAX(HYPOT(probe.offset_xy.x, probe.offset_xy.y), MIN_PROBE_EDGE)) + FLOOR((DELTA_PRINTABLE_RADIUS) - _MAX(HYPOT(probe.offset_xy.x, probe.offset_xy.y), PROBING_MARGIN)) #else DELTA_PRINTABLE_RADIUS #endif diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 7b920ab82c..0f8ce4a35e 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -54,11 +54,11 @@ public: // Note: This won't work on SCARA since the probe offset rotates with the arm. static inline bool can_reach(const float &rx, const float &ry) { return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) // The nozzle can go where it needs to go? - && position_is_reachable(rx, ry, ABS(MIN_PROBE_EDGE)); // Can the nozzle also go near there? + && position_is_reachable(rx, ry, ABS(PROBING_MARGIN)); // Can the nozzle also go near there? } #else FORCE_INLINE static bool can_reach(const float &rx, const float &ry) { - return position_is_reachable(rx, ry, MIN_PROBE_EDGE); + return position_is_reachable(rx, ry, PROBING_MARGIN); } #endif @@ -131,7 +131,7 @@ public: ); static inline float probe_radius() { - return printable_radius - _MAX(MIN_PROBE_EDGE, HYPOT(offset_xy.x, offset_xy.y)); + return printable_radius - _MAX(PROBING_MARGIN, HYPOT(offset_xy.x, offset_xy.y)); } #endif @@ -140,7 +140,7 @@ public: #if IS_KINEMATIC (X_CENTER) - probe_radius() #else - _MAX((X_MIN_BED) + (MIN_PROBE_EDGE_LEFT), (X_MIN_POS) + offset_xy.x) + _MAX((X_MIN_BED) + (PROBING_MARGIN_LEFT), (X_MIN_POS) + offset_xy.x) #endif ); } @@ -149,7 +149,7 @@ public: #if IS_KINEMATIC (X_CENTER) + probe_radius() #else - _MIN((X_MAX_BED) - (MIN_PROBE_EDGE_RIGHT), (X_MAX_POS) + offset_xy.x) + _MIN((X_MAX_BED) - (PROBING_MARGIN_RIGHT), (X_MAX_POS) + offset_xy.x) #endif ); } @@ -158,7 +158,7 @@ public: #if IS_KINEMATIC (Y_CENTER) - probe_radius() #else - _MAX((Y_MIN_BED) + (MIN_PROBE_EDGE_FRONT), (Y_MIN_POS) + offset_xy.y) + _MAX((Y_MIN_BED) + (PROBING_MARGIN_FRONT), (Y_MIN_POS) + offset_xy.y) #endif ); } @@ -167,7 +167,7 @@ public: #if IS_KINEMATIC (Y_CENTER) + probe_radius() #else - _MIN((Y_MAX_BED) - (MIN_PROBE_EDGE_BACK), (Y_MAX_POS) + offset_xy.y) + _MIN((Y_MAX_BED) - (PROBING_MARGIN_BACK), (Y_MAX_POS) + offset_xy.y) #endif ); } From 419f31f3713607d6867e342ee4e907f28112f945 Mon Sep 17 00:00:00 2001 From: cccc Date: Wed, 3 Jun 2020 10:03:59 +0800 Subject: [PATCH 0572/1454] SoftwareSerialM for MEEB (#18178) --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index a8948024b8..78dc01bf0a 100644 --- a/platformio.ini +++ b/platformio.ini @@ -297,7 +297,7 @@ build_flags = ${common_stm32f1.build_flags} -DGENERIC_BOOTLOADER extra_scripts = pre:buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP_create_variant.py buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py -lib_deps = ${common.lib_deps} +lib_deps = ${common_stm32f1.lib_deps} USBComposite for STM32F1@==0.91 Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use lib_ignore = SPI, LiquidCrystal From 8477dbf65db4572d6aac07f5c732130607f31545 Mon Sep 17 00:00:00 2001 From: George Fu Date: Wed, 3 Jun 2020 10:04:22 +0800 Subject: [PATCH 0573/1454] Update FYSETC STM32F103 ldscript and script (#18179) --- .../{fysetc_aio_ii.ld => fysetc_stm32f103rc.ld} | 2 +- .../share/PlatformIO/scripts/STM32F103RC_fysetc.py | 13 ++++++++++--- 2 files changed, 11 insertions(+), 4 deletions(-) rename buildroot/share/PlatformIO/ldscripts/{fysetc_aio_ii.ld => fysetc_stm32f103rc.ld} (88%) diff --git a/buildroot/share/PlatformIO/ldscripts/fysetc_aio_ii.ld b/buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld similarity index 88% rename from buildroot/share/PlatformIO/ldscripts/fysetc_aio_ii.ld rename to buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld index f279347ee5..7122acb3b6 100644 --- a/buildroot/share/PlatformIO/ldscripts/fysetc_aio_ii.ld +++ b/buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld @@ -5,7 +5,7 @@ MEMORY { ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - rom (rx) : ORIGIN = 0x08010000, LENGTH = 256K - 40K - 4K + rom (rx) : ORIGIN = 0x08010000, LENGTH = 256K - 64K } /* Provide memory region aliases for common.inc */ diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 134f63d668..a66c18a5e2 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -1,14 +1,21 @@ +import os from os.path import join from os.path import expandvars -Import("env", "projenv") +Import("env") # Relocate firmware from 0x08000000 to 0x08010000 -# for define in env['CPPDEFINES']: +#for define in env['CPPDEFINES']: # if define[0] == "VECT_TAB_ADDR": # env['CPPDEFINES'].remove(define) -#env['CPPDEFINES'].remove(("VECT_TAB_ADDR", 134217728)) #env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08010000")) +#custom_ld_script = os.path.abspath("buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld") +#for i, flag in enumerate(env["LINKFLAGS"]): +# if "-Wl,-T" in flag: +# env["LINKFLAGS"][i] = "-Wl,-T" + custom_ld_script +# elif flag == "-T": +# env["LINKFLAGS"][i + 1] = custom_ld_script + # Custom HEX from ELF env.AddPostAction( join("$BUILD_DIR","${PROGNAME}.elf"), From 6f90967780baeb369f6ffdc14a41c3b3e8ff5e84 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 4 Jun 2020 00:06:15 +0000 Subject: [PATCH 0574/1454] [cron] Bump distribution date (2020-06-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4a3af243f0..67d100aa12 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-06-03" + #define STRING_DISTRIBUTION_DATE "2020-06-04" #endif /** From 076b2112a39966e3c5781dfcec393c90b70303ce Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Thu, 4 Jun 2020 06:20:19 +0200 Subject: [PATCH 0575/1454] Fix spindle power LCD display (#18189) --- Marlin/src/feature/spindle_laser_types.h | 2 ++ Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index 7fa93420d1..3b34924db2 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -38,10 +38,12 @@ #define cutter_power_t uint16_t #define cutter_setPower_t uint16_t #define CUTTER_MENU_POWER_TYPE uint16_5 + #define cutter_power2str ui16tostr5rj #else #define cutter_power_t uint8_t #define cutter_setPower_t uint8_t #define CUTTER_MENU_POWER_TYPE uint8 + #define cutter_power2str ui8tostr3rj #endif #if ENABLED(MARLIN_DEV_MODE) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index fc67f9432a..69827edfad 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -542,7 +542,7 @@ void MarlinUI::draw_status_screen() { // Laser / Spindle #if DO_DRAW_CUTTER if (cutter.power && PAGE_CONTAINS(STATUS_CUTTER_TEXT_Y - INFO_FONT_ASCENT, STATUS_CUTTER_TEXT_Y - 1)) { - lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3rj(cutter.power)); + lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.power)); #if CUTTER_DISPLAY_IS(PERCENT) lcd_put_wchar('%'); #elif CUTTER_DISPLAY_IS(RPM) From d5bfc5b07beb624d30fbed15b6eb4d2b258e5095 Mon Sep 17 00:00:00 2001 From: grauerfuchs <42082416+grauerfuchs@users.noreply.github.com> Date: Thu, 4 Jun 2020 00:23:53 -0400 Subject: [PATCH 0576/1454] Fix Mightyboard envs (#18194) --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 78dc01bf0a..4ecf0e3df7 100644 --- a/platformio.ini +++ b/platformio.ini @@ -94,7 +94,7 @@ board = megaatmega1280 [env:MightyBoard1280] platform = atmelavr extends = common_avr8 -board = megaatmega1280 +board = ATmega1280 upload_speed = 57600 # @@ -103,7 +103,7 @@ upload_speed = 57600 [env:MightyBoard2560] platform = atmelavr extends = common_avr8 -board = megaatmega2560 +board = ATmega2560 upload_protocol = wiring upload_speed = 57600 board_upload.maximum_size = 253952 From 2d1cbf8e1d9f4d55f79b5c5d0628965472a7f92e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Jun 2020 03:14:18 -0500 Subject: [PATCH 0577/1454] Add comment to M281 --- Marlin/src/gcode/config/M281.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index e925cd5b12..22ca8a4c13 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -26,6 +26,13 @@ #include "../gcode.h" #include "../../module/servo.h" +/** + * M281 - Edit / Report Servo Angles + * + * P - Servo to update + * L - Deploy Angle + * U - Stowed Angle + */ void GcodeSuite::M281() { if (!parser.seenval('P')) return; const int servo_index = parser.value_int(); From a500862dc6a01696d554e4f714782340fbc17d54 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 5 Jun 2020 00:08:38 +0000 Subject: [PATCH 0578/1454] [cron] Bump distribution date (2020-06-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 67d100aa12..995599b3ad 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-06-04" + #define STRING_DISTRIBUTION_DATE "2020-06-05" #endif /** From fcb8c5a1c1220c0f9c48fcecdd848a060c998703 Mon Sep 17 00:00:00 2001 From: MoellerDi Date: Fri, 5 Jun 2020 02:09:01 +0200 Subject: [PATCH 0579/1454] Fix G34 move in wrong direction (#18188) --- Marlin/src/gcode/calibrate/G34_M422.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 0961cce59c..d0fa84b9ad 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -294,11 +294,14 @@ void GcodeSuite::G34() { // Check for less accuracy compared to last move if (last_z_align_move[zstepper] < z_align_abs * 0.7f) { SERIAL_ECHOLNPGM("Decreasing accuracy detected."); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " last_z_align_move = ", last_z_align_move[zstepper]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " z_align_abs = ", z_align_abs); adjustment_reverse = !adjustment_reverse; } - // Remember the alignment for the next iteration - last_z_align_move[zstepper] = z_align_abs; + // Remember the alignment for the next iteration, but only if steppers move, + // otherwise it would be just zero (in case this stepper was at z_measured_min already) + if (z_align_abs > 0) last_z_align_move[zstepper] = z_align_abs; #endif // Stop early if all measured points achieve accuracy target @@ -312,8 +315,10 @@ void GcodeSuite::G34() { #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) // Decreasing accuracy was detected so move was inverted. // Will match reversed Z steppers on dual steppers. Triple will need more work to map. - if (adjustment_reverse) + if (adjustment_reverse) { z_align_move = -z_align_move; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " correction reversed to ", z_align_move); + } #endif // Do a move to correct part of the misalignment for the current stepper From 9e2f142391c762666b0152785d8085ee08a007bc Mon Sep 17 00:00:00 2001 From: git-user44 <22965693+git-user44@users.noreply.github.com> Date: Fri, 5 Jun 2020 01:55:39 +0100 Subject: [PATCH 0580/1454] Clean up Melzi LCD timing defaults (#18187) Co-authored-by: Scott Lahteine --- Marlin/Makefile | 18 ++++++---- Marlin/src/core/boards.h | 17 +++++----- Marlin/src/pins/pins.h | 2 ++ .../src/pins/sanguino/pins_MELZI_CREALITY.h | 14 ++++---- Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h | 15 +++++---- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 13 ++++---- Marlin/src/pins/sanguino/pins_MELZI_V2.h | 33 +++++++++++++++++++ .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 24 ++++++++++---- 8 files changed, 95 insertions(+), 41 deletions(-) create mode 100644 Marlin/src/pins/sanguino/pins_MELZI_V2.h diff --git a/Marlin/Makefile b/Marlin/Makefile index 5f4fd34d57..8b18d278a1 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -361,34 +361,38 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1501) else ifeq ($(HARDWARE_MOTHERBOARD),1502) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega644p -# Melzi with ATmega1284 (MaKr3d version) +# Melzi V2.0 else ifeq ($(HARDWARE_MOTHERBOARD),1503) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p -# Melzi Creality3D board (for CR-10 etc) +# Melzi with ATmega1284 (MaKr3d version) else ifeq ($(HARDWARE_MOTHERBOARD),1504) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p -# Melzi Malyan M150 board +# Melzi Creality3D board (for CR-10 etc) else ifeq ($(HARDWARE_MOTHERBOARD),1505) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p -# Tronxy X5S +# Melzi Malyan M150 board else ifeq ($(HARDWARE_MOTHERBOARD),1506) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p -# STB V1.1 +# Tronxy X5S else ifeq ($(HARDWARE_MOTHERBOARD),1507) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p -# Azteeg X1 +# STB V1.1 else ifeq ($(HARDWARE_MOTHERBOARD),1508) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p -# Anet 1.0 (Melzi clone) +# Azteeg X1 else ifeq ($(HARDWARE_MOTHERBOARD),1509) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p +# Anet 1.0 (Melzi clone) +else ifeq ($(HARDWARE_MOTHERBOARD),1510) + HARDWARE_VARIANT ?= Sanguino + MCU ?= atmega1284p # # Other ATmega644P, ATmega644, ATmega1284P diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 644eeee54d..b2e04920bc 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -162,13 +162,14 @@ #define BOARD_SANGUINOLOLU_11 1500 // Sanguinololu < 1.2 #define BOARD_SANGUINOLOLU_12 1501 // Sanguinololu 1.2 and above #define BOARD_MELZI 1502 // Melzi -#define BOARD_MELZI_MAKR3D 1503 // Melzi with ATmega1284 (MaKr3d version) -#define BOARD_MELZI_CREALITY 1504 // Melzi Creality3D board (for CR-10 etc) -#define BOARD_MELZI_MALYAN 1505 // Melzi Malyan M150 board -#define BOARD_MELZI_TRONXY 1506 // Tronxy X5S -#define BOARD_STB_11 1507 // STB V1.1 -#define BOARD_AZTEEG_X1 1508 // Azteeg X1 -#define BOARD_ANET_10 1509 // Anet 1.0 (Melzi clone) +#define BOARD_MELZI_V2 1503 // Melzi V2 +#define BOARD_MELZI_MAKR3D 1504 // Melzi with ATmega1284 (MaKr3d version) +#define BOARD_MELZI_CREALITY 1505 // Melzi Creality3D board (for CR-10 etc) +#define BOARD_MELZI_MALYAN 1506 // Melzi Malyan M150 board +#define BOARD_MELZI_TRONXY 1507 // Tronxy X5S +#define BOARD_STB_11 1508 // STB V1.1 +#define BOARD_AZTEEG_X1 1509 // Azteeg X1 +#define BOARD_ANET_10 1510 // Anet 1.0 (Melzi clone) // // Other ATmega644P, ATmega644, ATmega1284P @@ -365,4 +366,4 @@ #define _MB_1(B) (defined(BOARD_##B) && MOTHERBOARD==BOARD_##B) #define MB(V...) DO(MB,||,V) -#define IS_MELZI MB(MELZI, MELZI_CREALITY, MELZI_MAKR3D, MELZI_MALYAN, MELZI_TRONXY) +#define IS_MELZI MB(MELZI, MELZI_CREALITY, MELZI_MAKR3D, MELZI_MALYAN, MELZI_TRONXY, MELZI_V2) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 6c19129f93..527f71734d 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -284,6 +284,8 @@ #include "sanguino/pins_SANGUINOLOLU_12.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI) #include "sanguino/pins_MELZI.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p +#elif MB(MELZI_V2) + #include "sanguino/pins_MELZI_V2.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_MAKR3D) #include "sanguino/pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_CREALITY) diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 10a52705e7..22546fc1ce 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -33,6 +33,13 @@ #define BOARD_INFO_NAME "Melzi (Creality)" +// Alter timing for graphical display +#if HAS_GRAPHICAL_LCD + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + #include "pins_MELZI.h" // @@ -58,13 +65,6 @@ #undef BEEPER_PIN #endif -// Alter timing for graphical display -#if HAS_GRAPHICAL_LCD - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) -#endif - #if ENABLED(MINIPANEL) #undef DOGLCD_CS #define DOGLCD_CS LCD_PINS_RS diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index 8e682453b4..1ceb8b920e 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -26,6 +26,14 @@ */ #define BOARD_INFO_NAME "Melzi (Malyan)" + +// Alter timing for graphical display +#if HAS_GRAPHICAL_LCD + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + #include "pins_MELZI.h" #undef LCD_SDSS @@ -42,10 +50,3 @@ #define BTN_EN1 30 #define BTN_EN2 29 #define BTN_ENC 28 - -// Alter timing for graphical display -#if HAS_GRAPHICAL_LCD - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) -#endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index 88b80dfb89..8da60593ab 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -26,6 +26,13 @@ */ #define BOARD_INFO_NAME "Melzi (Tronxy)" + +#if HAS_GRAPHICAL_LCD + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(0) +#endif + #include "pins_MELZI.h" #undef Z_ENABLE_PIN @@ -50,9 +57,3 @@ #define BTN_EN1 10 #define BTN_EN2 11 #define BTN_ENC 26 - -#if HAS_GRAPHICAL_LCD - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) -#endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h new file mode 100644 index 0000000000..7db9a2e810 --- /dev/null +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Melzi V2.0 as found at https://www.reprap.org/wiki/Melzi + */ + +#define BOARD_INFO_NAME "Melzi V2" + +#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #define BOARD_ST7920_DELAY_3 DELAY_NS(0) +#endif + +#include "pins_MELZI.h" diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 47c1f21416..d5f09bd10b 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -166,9 +166,15 @@ #define LCD_PINS_ENABLE 16 #define LCD_PINS_D4 11 - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(0) + #endif #elif ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 @@ -182,9 +188,15 @@ #define BEEPER_PIN 27 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(0) + #endif #endif #else // Sanguinololu >=1.3 From f350e9d0cb6387705cc44d1aa8031958469ae3fa Mon Sep 17 00:00:00 2001 From: Leo Date: Fri, 5 Jun 2020 04:29:47 +0200 Subject: [PATCH 0581/1454] Shorter BTT board names (for LCD info) (#18139) --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h | 2 +- 12 files changed, 12 insertions(+), 12 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 4f4927f312..1ff94e93d2 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -21,7 +21,7 @@ */ #pragma once -#define BOARD_INFO_NAME "BIGTREE SKR 1.1" +#define BOARD_INFO_NAME "BTT SKR V1.1" // // Limit Switches diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 48b9711366..0503defa9a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -21,7 +21,7 @@ */ #pragma once -#define BOARD_INFO_NAME "BIGTREE SKR 1.3" +#define BOARD_INFO_NAME "BTT SKR V1.3" // // Trinamic Stallguard pins diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 85e477a5c2..e2801ebfa6 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -22,7 +22,7 @@ #pragma once #ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "BIGTREE SKR 1.4" + #define BOARD_INFO_NAME "BTT SKR V1.4" #endif // diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h index 937ba56bb7..8255a55f02 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h @@ -21,7 +21,7 @@ */ #pragma once -#define BOARD_INFO_NAME "BIGTREE SKR 1.4 TURBO" +#define BOARD_INFO_NAME "BTT SKR V1.4 TURBO" #define SKR_HAS_LPC1769 // diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 05600a9a9d..7fb1c48bec 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -25,7 +25,7 @@ #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif -#define BOARD_INFO_NAME "BIGTREE SKR E3 DIP V1.0" +#define BOARD_INFO_NAME "BTT SKR E3 DIP V1.0" // Release PB3/PB4 (TMC_SW Pins) from JTAG pins #define DISABLE_JTAG diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h index f909cce83a..7adce168dc 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h @@ -23,7 +23,7 @@ #include "pins_BTT_SKR_MINI_E3.h" -#define BOARD_INFO_NAME "BIGTREE SKR Mini E3" +#define BOARD_INFO_NAME "BTT SKR Mini E3 V1.0" /** * TMC220x stepper drivers diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h index 961620ee8b..5d649bce7f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h @@ -23,7 +23,7 @@ #include "pins_BTT_SKR_MINI_E3.h" -#define BOARD_INFO_NAME "BIGTREE SKR Mini E3 V1.2" +#define BOARD_INFO_NAME "BTT SKR Mini E3 V1.2" #define NEOPIXEL_PIN PC7 // LED driving pin diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h index 1d5cf0f653..57d964ee20 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h @@ -32,7 +32,7 @@ #include "pins_BTT_SKR_MINI_E3.h" -#define BOARD_INFO_NAME "BIGTREE SKR Mini E3 V2.0" +#define BOARD_INFO_NAME "BTT SKR Mini E3 V2.0" // Release PA13/PA14 (led, usb control) from SWD pins #define DISABLE_DEBUG diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index cd0ff58a29..59a9de7078 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -25,7 +25,7 @@ #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif -#define BOARD_INFO_NAME "BIGTREE SKR Mini 1.1" +#define BOARD_INFO_NAME "BTT SKR Mini V1.1" //#define DISABLE_DEBUG #define DISABLE_JTAG diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index ae4d611865..8a6afcc0f5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -27,7 +27,7 @@ #error "BIGTREE BTT002 V1.0 supports up to 1 hotends / E-steppers." #endif -#define BOARD_INFO_NAME "BIGTREE Btt002 1.0" +#define BOARD_INFO_NAME "BTT BTT002 V1.0" // Use one of these or SDCard-based Emulation will be used #if NO_EEPROM_SELECTED diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index d1d0ddc480..e2ecdae800 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -29,7 +29,7 @@ #error "Marlin extruder/hotends limit! Increase MAX_EXTRUDERS to continue." #endif -#define BOARD_INFO_NAME "BIGTREE GTR 1.0" +#define BOARD_INFO_NAME "BTT GTR V1.0" // Onboard I2C EEPROM #define I2C_EEPROM diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index ba1ea08796..ccb03e78e5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -27,7 +27,7 @@ #error "BIGTREE SKR Pro V1.1 supports up to 3 hotends / E-steppers." #endif -#define BOARD_INFO_NAME "BIGTREE SKR Pro 1.1" // redefined? +#define BOARD_INFO_NAME "BTT SKR Pro V1.1" // redefined? // Use one of these or SDCard-based Emulation will be used #if NO_EEPROM_SELECTED From 63717822637064b347d046f8f39be824eff51785 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 12 May 2020 05:50:28 -0500 Subject: [PATCH 0582/1454] Add HAS_MULTI_SERIAL conditional --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/core/serial.cpp | 2 +- Marlin/src/core/serial.h | 2 +- Marlin/src/feature/binary_protocol.h | 4 ++-- Marlin/src/gcode/config/M575.cpp | 6 +++--- Marlin/src/gcode/host/M118.cpp | 10 ++++------ Marlin/src/gcode/parser.cpp | 2 +- Marlin/src/gcode/queue.cpp | 30 ++++++++++------------------ Marlin/src/gcode/queue.h | 12 ++++------- Marlin/src/gcode/sd/M28_M29.cpp | 6 ++---- Marlin/src/inc/Conditionals_post.h | 2 ++ Marlin/src/sd/cardreader.cpp | 4 ++-- Marlin/src/sd/cardreader.h | 8 +++----- 13 files changed, 37 insertions(+), 53 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 3b07676840..3b0ba07c16 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -862,7 +862,7 @@ void setup() { MYSERIAL0.begin(BAUDRATE); uint32_t serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL MYSERIAL1.begin(BAUDRATE); serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 1d3907bc56..313d6ce20e 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -28,7 +28,7 @@ uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; static PGMSTR(errormagic, "Error:"); static PGMSTR(echomagic, "echo:"); -#if NUM_SERIAL > 1 +#if HAS_MULTI_SERIAL int8_t serial_port_index = 0; #endif diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 5f800c32cf..1a319e6322 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -47,7 +47,7 @@ extern uint8_t marlin_debug_flags; #define DEBUGGING(F) (marlin_debug_flags & (MARLIN_DEBUG_## F)) #define SERIAL_BOTH 0x7F -#if NUM_SERIAL > 1 +#if HAS_MULTI_SERIAL extern int8_t serial_port_index; #define _PORT_REDIRECT(n,p) REMEMBER(n,serial_port_index,p) #define _PORT_RESTORE(n) RESTORE(n) diff --git a/Marlin/src/feature/binary_protocol.h b/Marlin/src/feature/binary_protocol.h index c7850c4315..e9a723c1eb 100644 --- a/Marlin/src/feature/binary_protocol.h +++ b/Marlin/src/feature/binary_protocol.h @@ -32,7 +32,7 @@ inline bool bs_serial_data_available(const uint8_t index) { switch (index) { case 0: return MYSERIAL0.available(); - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL case 1: return MYSERIAL1.available(); #endif } @@ -42,7 +42,7 @@ inline bool bs_serial_data_available(const uint8_t index) { inline int bs_read_serial(const uint8_t index) { switch (index) { case 0: return MYSERIAL0.read(); - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL case 1: return MYSERIAL1.read(); #endif } diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index 947af14e30..a81d1e57c9 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -42,7 +42,7 @@ void GcodeSuite::M575() { if (set0) { SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(" Serial " - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , '0', #else "0" @@ -50,7 +50,7 @@ void GcodeSuite::M575() { " baud rate set to ", baud ); } - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL const bool set1 = (port == -99 || port == 1); if (set1) { SERIAL_ECHO_START(); @@ -62,7 +62,7 @@ void GcodeSuite::M575() { if (set0) { MYSERIAL0.end(); MYSERIAL0.begin(baud); } - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } #endif diff --git a/Marlin/src/gcode/host/M118.cpp b/Marlin/src/gcode/host/M118.cpp index ba52a4f816..81bb830d83 100644 --- a/Marlin/src/gcode/host/M118.cpp +++ b/Marlin/src/gcode/host/M118.cpp @@ -34,7 +34,7 @@ */ void GcodeSuite::M118() { bool hasE = false, hasA = false; - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL int8_t port = -1; // Assume no redirect #endif char *p = parser.string_arg; @@ -44,7 +44,7 @@ void GcodeSuite::M118() { switch (p[0]) { case 'A': hasA = true; break; case 'E': hasE = true; break; - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL case 'P': port = p[1] - '0'; break; #endif } @@ -52,7 +52,7 @@ void GcodeSuite::M118() { while (*p == ' ') ++p; } - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL const int8_t old_serial = serial_port_index; if (WITHIN(port, 0, NUM_SERIAL)) serial_port_index = ( @@ -69,7 +69,5 @@ void GcodeSuite::M118() { if (hasA) SERIAL_ECHOPGM("// "); SERIAL_ECHOLN(p); - #if NUM_SERIAL > 1 - serial_port_index = old_serial; - #endif + TERN_(HAS_MULTI_SERIAL, serial_port_index = old_serial); } diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 9a2272e747..a025cebc88 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -28,7 +28,7 @@ #include "../MarlinCore.h" -#if NUM_SERIAL > 1 +#if HAS_MULTI_SERIAL #include "queue.h" #endif diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index a4a4993556..24d1d2cf67 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -72,7 +72,7 @@ char GCodeQueue::command_buffer[BUFSIZE][MAX_CMD_SIZE]; /* * The port that the command was received on */ -#if NUM_SERIAL > 1 +#if HAS_MULTI_SERIAL int16_t GCodeQueue::port[BUFSIZE]; #endif @@ -119,14 +119,12 @@ void GCodeQueue::clear() { * Once a new command is in the ring buffer, call this to commit it */ void GCodeQueue::_commit_command(bool say_ok - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , int16_t p/*=-1*/ #endif ) { send_ok[index_w] = say_ok; - #if NUM_SERIAL > 1 - port[index_w] = p; - #endif + TERN_(HAS_MULTI_SERIAL, port[index_w] = p); TERN_(POWER_LOSS_RECOVERY, recovery.commit_sdpos(index_w)); if (++index_w >= BUFSIZE) index_w = 0; length++; @@ -138,14 +136,14 @@ void GCodeQueue::_commit_command(bool say_ok * Return false for a full buffer, or if the 'command' is a comment. */ bool GCodeQueue::_enqueue(const char* cmd, bool say_ok/*=false*/ - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , int16_t pn/*=-1*/ #endif ) { if (*cmd == ';' || length >= BUFSIZE) return false; strcpy(command_buffer[index_w], cmd); _commit_command(say_ok - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , pn #endif ); @@ -276,7 +274,7 @@ void GCodeQueue::enqueue_now_P(PGM_P const pgcode) { * B Block queue space remaining */ void GCodeQueue::ok_to_send() { - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL const int16_t pn = command_port(); if (pn < 0) return; PORT_REDIRECT(pn); // Reply to the serial port that sent the command @@ -303,30 +301,24 @@ void GCodeQueue::ok_to_send() { */ void GCodeQueue::flush_and_request_resend() { const int16_t pn = command_port(); - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL if (pn < 0) return; PORT_REDIRECT(pn); // Reply to the serial port that sent the command #endif SERIAL_FLUSH(); SERIAL_ECHOPGM(STR_RESEND); - - SERIAL_ECHOLN(last_N[pn] + 1); + SERIAL_ECHOLN(last_N[pn] + 1); ok_to_send(); } inline bool serial_data_available() { - return false - || MYSERIAL0.available() - #if NUM_SERIAL > 1 - || MYSERIAL1.available() - #endif - ; + return MYSERIAL0.available() || TERN0(HAS_MULTI_SERIAL, MYSERIAL1.available()); } inline int read_serial(const uint8_t index) { switch (index) { case 0: return MYSERIAL0.read(); - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL case 1: return MYSERIAL1.read(); #endif default: return -1; @@ -538,7 +530,7 @@ void GCodeQueue::get_serial_commands() { // Add the command to the queue _enqueue(serial_line_buffer[i], true - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , i #endif ); diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 6c14d7d3db..25731782d3 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -55,16 +55,12 @@ public: /** * The port that the command was received on */ - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL static int16_t port[BUFSIZE]; #endif static int16_t command_port() { - return (0 - #if NUM_SERIAL > 1 - + port[index_r] - #endif - ); + return TERN0(HAS_MULTI_SERIAL, port[index_r]); } GCodeQueue(); @@ -162,13 +158,13 @@ private: #endif static void _commit_command(bool say_ok - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , int16_t p=-1 #endif ); static bool _enqueue(const char* cmd, bool say_ok=false - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL , int16_t p=-1 #endif ); diff --git a/Marlin/src/gcode/sd/M28_M29.cpp b/Marlin/src/gcode/sd/M28_M29.cpp index 9dc192c09b..45e0782fa7 100644 --- a/Marlin/src/gcode/sd/M28_M29.cpp +++ b/Marlin/src/gcode/sd/M28_M29.cpp @@ -27,7 +27,7 @@ #include "../gcode.h" #include "../../sd/cardreader.h" -#if NUM_SERIAL > 1 +#if HAS_MULTI_SERIAL #include "../queue.h" #endif @@ -49,9 +49,7 @@ void GcodeSuite::M28() { // Binary transfer mode if ((card.flag.binary_mode = binary_mode)) { SERIAL_ECHO_MSG("Switching to Binary Protocol"); - #if NUM_SERIAL > 1 - card.transfer_port_index = queue.port[queue.index_r]; - #endif + TERN_(HAS_MULTI_SERIAL, card.transfer_port_index = queue.port[queue.index_r]); } else card.openFileWrite(p); diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index edc981520d..6fb546822b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2519,4 +2519,6 @@ #if !NUM_SERIAL #undef BAUD_RATE_GCODE +#elif NUM_SERIAL > 1 + #define HAS_MULTI_SERIAL 1 #endif diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 9ce2c5304c..9c662fd755 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -51,7 +51,7 @@ card_flags_t CardReader::flag; char CardReader::filename[FILENAME_LENGTH], CardReader::longFilename[LONG_FILENAME_LENGTH]; int8_t CardReader::autostart_index; -#if ENABLED(BINARY_FILE_TRANSFER) && NUM_SERIAL > 1 +#if BOTH(HAS_MULTI_SERIAL, BINARY_FILE_TRANSFER) int8_t CardReader::transfer_port_index; #endif @@ -1095,7 +1095,7 @@ void CardReader::fileHasFinished() { #if ENABLED(AUTO_REPORT_SD_STATUS) uint8_t CardReader::auto_report_sd_interval = 0; millis_t CardReader::next_sd_report_ms; - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL int8_t CardReader::auto_report_port; #endif diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index f783f96ca7..4f488e3148 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -61,7 +61,7 @@ public: // Fast! binary file transfer #if ENABLED(BINARY_FILE_TRANSFER) - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL static int8_t transfer_port_index; #else static constexpr int8_t transfer_port_index = 0; @@ -164,9 +164,7 @@ public: #if ENABLED(AUTO_REPORT_SD_STATUS) static void auto_report_sd_status(); static inline void set_auto_report_interval(uint8_t v) { - #if NUM_SERIAL > 1 - auto_report_port = serial_port_index; - #endif + TERN_(HAS_MULTI_SERIAL, auto_report_port = serial_port_index); NOMORE(v, 60); auto_report_sd_interval = v; next_sd_report_ms = millis() + 1000UL * v; @@ -258,7 +256,7 @@ private: #if ENABLED(AUTO_REPORT_SD_STATUS) static uint8_t auto_report_sd_interval; static millis_t next_sd_report_ms; - #if NUM_SERIAL > 1 + #if HAS_MULTI_SERIAL static int8_t auto_report_port; #endif #endif From bf25cc84127fcc18707ac5b2422087deff5bf3bd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 5 Jun 2020 16:17:06 -0500 Subject: [PATCH 0583/1454] Add a script to id configs --- buildroot/share/scripts/config-labels.py | 201 +++++++++++++++++++++++ 1 file changed, 201 insertions(+) create mode 100755 buildroot/share/scripts/config-labels.py diff --git a/buildroot/share/scripts/config-labels.py b/buildroot/share/scripts/config-labels.py new file mode 100755 index 0000000000..8effb54eed --- /dev/null +++ b/buildroot/share/scripts/config-labels.py @@ -0,0 +1,201 @@ +#!/usr/bin/env python +# +# for python3.5 or higher +#----------------------------------- +# Within Marlin project MarlinFirmware/Configurations, this program visits all folders +# under .../config/examples/*, processing each Configuration.h, Configuration_adv.h, +# _Bootscreen.h, and _Statusscreen.h, to insert: +# #define CONFIG_EXAMPLES_DIR "examples/