From b06f871dd094308828922039ea9923c89fd772a7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 21 Dec 2021 01:08:00 +0000 Subject: [PATCH 01/32] [cron] Bump distribution date (2021-12-21) --- 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 e952cf1ab3da..222ecc9393b9 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-12-20" +//#define STRING_DISTRIBUTION_DATE "2021-12-21" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a6019419b1d6..b5f62034aff2 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 "2021-12-20" + #define STRING_DISTRIBUTION_DATE "2021-12-21" #endif /** From f374fa0eb8cfa60981b25cb99856c14328fd703e Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Tue, 21 Dec 2021 01:26:31 -0600 Subject: [PATCH 02/32] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20FAST=5FPWM=5FFAN?= =?UTF-8?q?=20default=201KHz=20base=20freq.=20(#23326)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/inc/Conditionals_post.h | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 971318518d0f..7fb839550671 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2668,10 +2668,14 @@ #endif /** - * FAST PWM FAN Settings + * FAST PWM FAN default PWM frequency */ -#if ENABLED(FAST_PWM_FAN) && !defined(FAST_PWM_FAN_FREQUENCY) - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default +#if !defined(FAST_PWM_FAN_FREQUENCY) && ENABLED(FAST_PWM_FAN) + #ifdef __AVR__ + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) + #else + #define FAST_PWM_FAN_FREQUENCY 1000U + #endif #endif /** From 9cee62681232f154b411a606f1f49f0dd80a49ac Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 22 Dec 2021 13:48:38 +1300 Subject: [PATCH 03/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Chitu=20Z=5FSTOP=5FP?= =?UTF-8?q?IN=20(#23330)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index afe58df803d6..53b6797e91d2 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -23,6 +23,6 @@ #define BOARD_INFO_NAME "Chitu3D V5" -#define Z_STOP_PIN PG9 +#define Z_STOP_PIN PA14 #include "pins_CHITU3D_common.h" From fdd37a84a290bfd55311a200018e7fdcf63df079 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 22 Dec 2021 01:07:10 +0000 Subject: [PATCH 04/32] [cron] Bump distribution date (2021-12-22) --- 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 222ecc9393b9..ddabd7b152e7 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-12-21" +//#define STRING_DISTRIBUTION_DATE "2021-12-22" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b5f62034aff2..68cfee56e131 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 "2021-12-21" + #define STRING_DISTRIBUTION_DATE "2021-12-22" #endif /** From c1dba3d02888824400413fdf366c1fa574cbb587 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 22 Dec 2021 15:44:04 +1300 Subject: [PATCH 05/32] =?UTF-8?q?=E2=9C=A8=20Option=20to=20reset=20EEPROM?= =?UTF-8?q?=20on=20first=20run=20(#23276)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 1 + Marlin/src/module/settings.cpp | 76 ++++++++++++++----- .../PlatformIO/scripts/preflight-checks.py | 11 ++- 3 files changed, 68 insertions(+), 20 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 71a92113300c..bb89bc14a375 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1837,6 +1837,7 @@ #define EEPROM_BOOT_SILENT // Keep M503 quiet and only give errors during first load #if ENABLED(EEPROM_SETTINGS) //#define EEPROM_AUTO_INIT // Init EEPROM automatically on any errors. + //#define EEPROM_INIT_NOW // Init EEPROM on first boot after a new build. #endif // diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8ccf773adc28..a9c771240c25 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -36,7 +36,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V85" +#define EEPROM_VERSION "V86" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -198,20 +198,32 @@ static const feedRate_t _DMF[] PROGMEM = DEFAULT_MAX_FEEDRATE; */ typedef struct SettingsDataStruct { char version[4]; // Vnn\0 + #if ENABLED(EEPROM_INIT_NOW) + uint32_t build_hash; // Unique build hash + #endif uint16_t crc; // Data Checksum // // DISTINCT_E_FACTORS // - uint8_t esteppers; // DISTINCT_AXES - LINEAR_AXES + uint8_t e_factors; // DISTINCT_AXES - LINEAR_AXES + // + // Planner settings + // planner_settings_t planner_settings; xyze_float_t planner_max_jerk; // M205 XYZE planner.max_jerk float planner_junction_deviation_mm; // M205 J planner.junction_deviation_mm + // + // Home Offset + // xyz_pos_t home_offset; // M206 XYZ / M665 TPZ + // + // Hotend Offset + // #if HAS_HOTEND_OFFSET xyz_pos_t hotend_offset[HOTENDS - 1]; // M218 XYZ #endif @@ -649,13 +661,24 @@ void MarlinSettings::postprocess() { const char version[4] = EEPROM_VERSION; + #if ENABLED(EEPROM_INIT_NOW) + constexpr uint32_t strhash32(const char *s, const uint32_t h=0) { + return *s ? strhash32(s + 1, ((h + *s) << (*s & 3)) ^ *s) : h; + } + constexpr uint32_t build_hash = strhash32(__DATE__ __TIME__); + #endif + bool MarlinSettings::eeprom_error, MarlinSettings::validating; int MarlinSettings::eeprom_index; uint16_t MarlinSettings::working_crc; bool MarlinSettings::size_error(const uint16_t size) { if (size != datasize()) { - DEBUG_ERROR_MSG("EEPROM datasize error."); + DEBUG_ERROR_MSG("EEPROM datasize error." + #if ENABLED(MARLIN_DEV_MODE) + " (Actual:", size, " Expected:", datasize(), ")" + #endif + ); return true; } return false; @@ -675,13 +698,17 @@ void MarlinSettings::postprocess() { // Write or Skip version. (Flash doesn't allow rewrite without erase.) TERN(FLASH_EEPROM_EMULATION, EEPROM_SKIP, EEPROM_WRITE)(ver); - EEPROM_SKIP(working_crc); // Skip the checksum slot + #if ENABLED(EEPROM_INIT_NOW) + EEPROM_SKIP(build_hash); // Skip the hash slot + #endif + + EEPROM_SKIP(working_crc); // Skip the checksum slot working_crc = 0; // clear before first "real data" - const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - LINEAR_AXES; - _FIELD_TEST(esteppers); - EEPROM_WRITE(esteppers); + const uint8_t e_factors = DISTINCT_AXES - (LINEAR_AXES); + _FIELD_TEST(e_factors); + EEPROM_WRITE(e_factors); // // Planner Motion @@ -1494,6 +1521,9 @@ void MarlinSettings::postprocess() { eeprom_index = EEPROM_OFFSET; EEPROM_WRITE(version); + #if ENABLED(EEPROM_INIT_NOW) + EEPROM_WRITE(build_hash); + #endif EEPROM_WRITE(final_crc); // Report storage size @@ -1527,9 +1557,6 @@ void MarlinSettings::postprocess() { char stored_ver[4]; EEPROM_READ_ALWAYS(stored_ver); - uint16_t stored_crc; - EEPROM_READ_ALWAYS(stored_crc); - // Version has to match or defaults are used if (strncmp(version, stored_ver, 3) != 0) { if (stored_ver[3] != '\0') { @@ -1543,14 +1570,25 @@ void MarlinSettings::postprocess() { eeprom_error = true; } else { + + // Optionally reset on the first boot after flashing + #if ENABLED(EEPROM_INIT_NOW) + uint32_t stored_hash; + EEPROM_READ_ALWAYS(stored_hash); + if (stored_hash != build_hash) { EEPROM_FINISH(); return true; } + #endif + + uint16_t stored_crc; + EEPROM_READ_ALWAYS(stored_crc); + float dummyf = 0; working_crc = 0; // Init to 0. Accumulated by EEPROM_READ - _FIELD_TEST(esteppers); + _FIELD_TEST(e_factors); - // Number of esteppers may change - uint8_t esteppers; - EEPROM_READ_ALWAYS(esteppers); + // Number of e_factors may change + uint8_t e_factors; + EEPROM_READ_ALWAYS(e_factors); // // Planner Motion @@ -1558,16 +1596,16 @@ void MarlinSettings::postprocess() { { // Get only the number of E stepper parameters previously stored // Any steppers added later are set to their defaults - uint32_t tmp1[LINEAR_AXES + esteppers]; - float tmp2[LINEAR_AXES + esteppers]; - feedRate_t tmp3[LINEAR_AXES + esteppers]; + uint32_t tmp1[LINEAR_AXES + e_factors]; + float tmp2[LINEAR_AXES + e_factors]; + feedRate_t tmp3[LINEAR_AXES + e_factors]; EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2 EEPROM_READ(planner.settings.min_segment_time_us); EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s if (!validating) LOOP_DISTINCT_AXES(i) { - const bool in = (i < esteppers + LINEAR_AXES); + const bool in = (i < e_factors + LINEAR_AXES); planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]); planner.settings.axis_steps_per_mm[i] = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]); planner.settings.max_feedrate_mm_s[i] = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]); @@ -2496,7 +2534,7 @@ void MarlinSettings::postprocess() { return success; } reset(); - #if ENABLED(EEPROM_AUTO_INIT) + #if EITHER(EEPROM_AUTO_INIT, EEPROM_INIT_NOW) (void)save(); SERIAL_ECHO_MSG("EEPROM Initialized"); #endif diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 1837a7580d24..9f38ffe8bfa2 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -81,10 +81,19 @@ def sanity_check_target(): # # Give warnings on every build # - warnfile = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src", "inc", "Warnings.cpp.o") + srcpath = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src") + warnfile = os.path.join(srcpath, "inc", "Warnings.cpp.o") if os.path.exists(warnfile): os.remove(warnfile) + # + # Rebuild 'settings.cpp' for EEPROM_INIT_NOW + # + if 'EEPROM_INIT_NOW' in env['MARLIN_FEATURES']: + setfile = os.path.join(srcpath, "module", "settings.cpp.o") + if os.path.exists(setfile): + os.remove(setfile) + # # Check for old files indicating an entangled Marlin (mixing old and new code) # From 2893048e2955963bb307a4ca67ec26bb336de2f5 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Tue, 21 Dec 2021 23:09:55 -0500 Subject: [PATCH 06/32] =?UTF-8?q?=E2=9C=A8=20BLTouch=20High=20Speed=20mode?= =?UTF-8?q?=20runtime=20configuration=20(#22916)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 6 ++- Marlin/src/feature/bltouch.cpp | 24 ++++++------ Marlin/src/feature/bltouch.h | 15 +++++--- Marlin/src/gcode/bedlevel/G35.cpp | 6 ++- Marlin/src/gcode/calibrate/G34_M422.cpp | 6 ++- Marlin/src/gcode/probe/M401_M402.cpp | 20 ++++++++-- Marlin/src/inc/SanityCheck.h | 3 ++ Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_bed_corners.cpp | 21 ++++++----- Marlin/src/lcd/menu/menu_configuration.cpp | 14 +++++-- Marlin/src/lcd/menu/menu_tramming.cpp | 6 ++- Marlin/src/module/motion.cpp | 9 +++-- Marlin/src/module/probe.cpp | 17 ++++++--- Marlin/src/module/settings.cpp | 43 ++++++++++++++++------ 14 files changed, 132 insertions(+), 59 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 1878a6f25876..e50e0cde8954 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -897,12 +897,14 @@ //#define BLTOUCH_FORCE_MODE_SET /** - * Use "HIGH SPEED" mode for probing. + * Enable "HIGH SPEED" option for probing. * Danger: Disable if your probe sometimes fails. Only suitable for stable well-adjusted systems. * This feature was designed for Deltabots with very fast Z moves; however, higher speed Cartesians * might be able to use it. If the machine can't raise Z fast enough the BLTouch may go into ALARM. + * + * Set the default state here, change with 'M401 S' or UI, use M500 to save, M502 to reset. */ - //#define BLTOUCH_HS_MODE + //#define BLTOUCH_HS_MODE true // Safety: Enable voltage mode settings in the LCD menu. //#define BLTOUCH_LCD_VOLTAGE_MENU diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index 49a10f62b155..d3348e79f0b9 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -28,7 +28,12 @@ BLTouch bltouch; -bool BLTouch::last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain +bool BLTouch::od_5v_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain +#ifdef BLTOUCH_HS_MODE + bool BLTouch::high_speed_mode; // Initialized by settings.load, 0 = Low Speed; 1 = High Speed +#else + constexpr bool BLTouch::high_speed_mode; +#endif #include "../module/servo.h" #include "../module/probe.h" @@ -64,17 +69,14 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPGM("last_written_mode - ", last_written_mode); - DEBUG_ECHOLNPGM("config mode - " - #if ENABLED(BLTOUCH_SET_5V_MODE) - "BLTOUCH_SET_5V_MODE" - #else - "OD" - #endif - ); + PGMSTR(mode0, "OD"); + PGMSTR(mode1, "5V"); + DEBUG_ECHOPGM("BLTouch Mode: "); + DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); } - const bool should_set = last_written_mode != ENABLED(BLTOUCH_SET_5V_MODE); + const bool should_set = od_5v_mode != ENABLED(BLTOUCH_SET_5V_MODE); #endif @@ -193,7 +195,7 @@ void BLTouch::mode_conv_proc(const bool M5V) { _mode_store(); if (M5V) _set_5V_mode(); else _set_OD_mode(); _stow(); - last_written_mode = M5V; + od_5v_mode = M5V; } #endif // BLTOUCH diff --git a/Marlin/src/feature/bltouch.h b/Marlin/src/feature/bltouch.h index 9ecccb4256f4..ae3ab6630036 100644 --- a/Marlin/src/feature/bltouch.h +++ b/Marlin/src/feature/bltouch.h @@ -23,10 +23,6 @@ #include "../inc/MarlinConfigPre.h" -#if DISABLED(BLTOUCH_HS_MODE) - #define BLTOUCH_SLOW_MODE 1 -#endif - // BLTouch commands are sent as servo angles typedef unsigned char BLTCommand; @@ -70,8 +66,17 @@ typedef unsigned char BLTCommand; class BLTouch { public: + static void init(const bool set_voltage=false); - static bool last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain + static bool od_5v_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain + + #ifdef BLTOUCH_HS_MODE + static bool high_speed_mode; // Initialized by settings.load, 0 = Low Speed; 1 = High Speed + #else + static constexpr bool high_speed_mode = false; + #endif + + static inline float z_extra_clearance() { return high_speed_mode ? 7 : 0; } // DEPLOY and STOW are wrapped for error handling - these are used by homing and by probing static bool deploy() { return deploy_proc(); } diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index e45e18b7fbc2..8cabb923825a 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -33,6 +33,10 @@ #include "../../module/tool_change.h" #endif +#if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" @@ -102,7 +106,7 @@ void GcodeSuite::G35() { // In BLTOUCH HS mode, the probe travels in a deployed state. // Users of G35 might have a badly misaligned bed, so raise Z by the // length of the deployed pin (BLTOUCH stroke < 7mm) - do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, Z_CLEARANCE_BETWEEN_PROBES, 7)); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES + TERN0(BLTOUCH, bltouch.z_extra_clearance())); const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE, 0, true); if (isnan(z_probed_height)) { diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 8f4eab2c9715..328a40dbb46a 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -45,6 +45,10 @@ #include "../../libs/least_squares_fit.h" #endif +#if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" @@ -149,7 +153,7 @@ void GcodeSuite::G34() { // 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)) + #define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + TERN0(BLTOUCH, bltouch.z_extra_clearance())) // Compute a worst-case clearance height to probe from. After the first // iteration this will be re-calculated based on the actual bed position diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp index bd9bb44c4061..7cbae76f4b88 100644 --- a/Marlin/src/gcode/probe/M401_M402.cpp +++ b/Marlin/src/gcode/probe/M401_M402.cpp @@ -28,13 +28,27 @@ #include "../../module/motion.h" #include "../../module/probe.h" +#ifdef BLTOUCH_HS_MODE + #include "../../feature/bltouch.h" +#endif + /** * M401: Deploy and activate the Z probe + * + * With BLTOUCH_HS_MODE: + * S Set High Speed (HS) Mode and exit without deploy */ void GcodeSuite::M401() { - probe.deploy(); - TERN_(PROBE_TARE, probe.tare()); - report_current_position(); + if (parser.seen('S')) { + #ifdef BLTOUCH_HS_MODE + bltouch.high_speed_mode = parser.value_bool(); + #endif + } + else { + probe.deploy(); + TERN_(PROBE_TARE, probe.tare()); + report_current_position(); + } } /** diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index a809fad132b3..fbc0e3d1f04d 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1577,6 +1577,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif + #if ENABLED(BLTOUCH_HS_MODE) && BLTOUCH_HS_MODE == 0 + #error "BLTOUCH_HS_MODE must now be defined as true or false, indicating the default state." + #endif #if BLTOUCH_DELAY < 200 #error "BLTOUCH_DELAY less than 200 is unsafe and is not supported." #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 89b8fd7d7787..1d8861b2c700 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -491,6 +491,7 @@ namespace Language_en { LSTR MSG_BLTOUCH_STOW = _UxGT("Stow"); LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + LSTR MSG_BLTOUCH_SPEED_MODE = _UxGT("High Speed"); LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 7bf247f40be2..574097863956 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -217,13 +217,13 @@ static void _lcd_level_bed_corners_get_next_position() { bool _lcd_level_bed_corners_probe(bool verify=false) { if (verify) do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); // do clearance if needed - TERN_(BLTOUCH_SLOW_MODE, bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action do_blocking_move_to_z(last_z - LEVEL_CORNERS_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered endstops.hit_on_purpose(); set_current_from_steppers_for_axis(Z_AXIS); sync_plan_position(); - TERN_(BLTOUCH_SLOW_MODE, bltouch.stow()); // Stow in LOW SPEED MODE on every trigger + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); // Stow in LOW SPEED MODE on every trigger // Triggered outside tolerance range? if (ABS(current_position.z - last_z) > LEVEL_CORNERS_PROBE_TOLERANCE) { last_z = current_position.z; // Above tolerance. Set a new Z for subsequent corners. @@ -249,7 +249,7 @@ static void _lcd_level_bed_corners_get_next_position() { } idle(); } - TERN_(BLTOUCH_SLOW_MODE, bltouch.stow()); + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); ui.goto_screen(_lcd_draw_probing); return (probe_triggered); } @@ -263,13 +263,14 @@ static void _lcd_level_bed_corners_get_next_position() { do { ui.refresh(LCDVIEW_REDRAW_NOW); _lcd_draw_probing(); // update screen with # of good points - do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, current_position.z + LEVEL_CORNERS_Z_HOP, 7)); // clearance + + do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP + TERN0(BLTOUCH, bltouch.z_extra_clearance())); // clearance _lcd_level_bed_corners_get_next_position(); // Select next corner coordinates current_position -= probe.offset_xy; // Account for probe offsets do_blocking_move_to_xy(current_position); // Goto corner - TERN_(BLTOUCH_HS_MODE, bltouch.deploy()); // Deploy in HIGH SPEED MODE + TERN_(BLTOUCH, if (bltouch.high_speed_mode) bltouch.deploy()); // Deploy in HIGH SPEED MODE if (!_lcd_level_bed_corners_probe()) { // Probe down to tolerance if (_lcd_level_bed_corners_raise()) { // Prompt user to raise bed if needed #if ENABLED(LEVEL_CORNERS_VERIFY_RAISED) // Verify @@ -290,10 +291,12 @@ static void _lcd_level_bed_corners_get_next_position() { } while (good_points < nr_edge_points); // loop until all points within tolerance - #if ENABLED(BLTOUCH_HS_MODE) - // In HIGH SPEED MODE do clearance and stow at the very end - do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); - bltouch.stow(); + #if ENABLED(BLTOUCH) + if (bltouch.high_speed_mode) + // In HIGH SPEED MODE do clearance and stow at the very end + do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); + bltouch.stow(); + } #endif ui.goto_screen(_lcd_draw_level_prompt); // prompt for bed leveling diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index cd8bad9c8ba4..19b3dcbafbbe 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -217,11 +217,14 @@ void menu_advanced_settings(); #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) void bltouch_report() { - SERIAL_ECHOLNPGM("EEPROM Last BLTouch Mode - ", bltouch.last_written_mode); - SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD")); + PGMSTR(mode0, "OD"); + PGMSTR(mode1, "5V"); + SERIAL_ECHOPGM("BLTouch Mode: "); + SERIAL_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + SERIAL_ECHOLNPGM(" (Default " 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")); + strcpy_P(mess, PSTR("BLTouch Mode: ")); + strcpy_P(&mess[15], bltouch.od_5v_mode ? mode1 : mode0); ui.set_status(mess); ui.return_to_status(); } @@ -235,6 +238,9 @@ void menu_advanced_settings(); ACTION_ITEM(MSG_BLTOUCH_DEPLOY, bltouch._deploy); ACTION_ITEM(MSG_BLTOUCH_STOW, bltouch._stow); ACTION_ITEM(MSG_BLTOUCH_SW_MODE, bltouch._set_SW_mode); + #ifdef BLTOUCH_HS_MODE + EDIT_ITEM(bool, MSG_BLTOUCH_SPEED_MODE, &bltouch.high_speed_mode); + #endif #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) CONFIRM_ITEM(MSG_BLTOUCH_5V_MODE, MSG_BLTOUCH_5V_MODE, MSG_BUTTON_CANCEL, bltouch._set_5V_mode, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); CONFIRM_ITEM(MSG_BLTOUCH_OD_MODE, MSG_BLTOUCH_OD_MODE, MSG_BUTTON_CANCEL, bltouch._set_OD_mode, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index 8e9d4b3942b6..4033421b5673 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -36,6 +36,10 @@ #include "../../module/probe.h" #include "../../gcode/queue.h" +#if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" +#endif + //#define DEBUG_OUT 1 #include "../../core/debug_out.h" @@ -51,7 +55,7 @@ static int8_t reference_index; // = 0 static bool probe_single_point() { do_blocking_move_to_z(TERN(BLTOUCH, Z_CLEARANCE_DEPLOY_PROBE, Z_CLEARANCE_BETWEEN_PROBES)); // Stow after each point with BLTouch "HIGH SPEED" mode for push-pin safety - const float z_probed_height = probe.probe_at_point(tramming_points[tram_index], TERN(BLTOUCH_HS_MODE, PROBE_PT_STOW, PROBE_PT_RAISE), 0, true); + const float z_probed_height = probe.probe_at_point(tramming_points[tram_index], TERN0(BLTOUCH, bltouch.high_speed_mode) ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, true); z_measured[tram_index] = z_probed_height; if (reference_index < 0) reference_index = tram_index; move_to_tramming_wait_pos(); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 9ff668bf30d2..2248c52d85d9 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1803,8 +1803,8 @@ void prepare_line_to_destination() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home Fast: ", move_length, "mm"); do_homing_move(axis, move_length, 0.0, !use_probe_bump); - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) - if (axis == Z_AXIS) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS && !bltouch.high_speed_mode) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) #endif // If a second homing move is configured... @@ -1837,8 +1837,9 @@ void prepare_line_to_destination() { } #endif - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) - if (axis == Z_AXIS && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS && !bltouch.high_speed_mode && bltouch.deploy()) + return; // Intermediate DEPLOY (in LOW SPEED MODE) #endif // Slow move towards endstop until triggered diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 7e08db7a5b6e..540b4e1ae6a4 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -489,8 +489,10 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if BOTH(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) thermalManager.wait_for_hotend_heating(active_extruder); #endif - - if (TERN0(BLTOUCH_SLOW_MODE, bltouch.deploy())) return true; // Deploy in LOW SPEED MODE on every probe action + #if ENABLED(BLTOUCH) + if (!bltouch.high_speed_mode && bltouch.deploy()) + return true; // Deploy in LOW SPEED MODE on every probe action + #endif // Disable stealthChop if used. Enable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) @@ -531,8 +533,10 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { set_homing_current(false); #endif - if (probe_triggered && TERN0(BLTOUCH_SLOW_MODE, bltouch.stow())) // Stow in LOW SPEED MODE on every trigger - return true; + #if ENABLED(BLTOUCH) + if (probe_triggered && !bltouch.high_speed_mode && bltouch.stow()) + return true; // Stow in LOW SPEED MODE on every trigger + #endif // Clear endstop flags endstops.hit_on_purpose(); @@ -762,8 +766,9 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai DEBUG_POS("", current_position); } - #if BOTH(BLTOUCH, BLTOUCH_HS_MODE) - if (bltouch.triggered()) bltouch._reset(); + #if ENABLED(BLTOUCH) + if (bltouch.high_speed_mode && bltouch.triggered()) + bltouch._reset(); #endif // On delta keep Z below clip height or do_blocking_move_to will abort diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index a9c771240c25..8a32d4c57ea7 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -301,7 +301,10 @@ typedef struct SettingsDataStruct { // // BLTOUCH // - bool bltouch_last_written_mode; + bool bltouch_od_5v_mode; + #ifdef BLTOUCH_HS_MODE + bool bltouch_high_speed_mode; // M401 S + #endif // // Kinematic Settings @@ -918,9 +921,15 @@ void MarlinSettings::postprocess() { // BLTOUCH // { - _FIELD_TEST(bltouch_last_written_mode); - const bool bltouch_last_written_mode = TERN(BLTOUCH, bltouch.last_written_mode, false); - EEPROM_WRITE(bltouch_last_written_mode); + _FIELD_TEST(bltouch_od_5v_mode); + const bool bltouch_od_5v_mode = TERN0(BLTOUCH, bltouch.od_5v_mode); + EEPROM_WRITE(bltouch_od_5v_mode); + + #ifdef BLTOUCH_HS_MODE + _FIELD_TEST(bltouch_high_speed_mode); + const bool bltouch_high_speed_mode = TERN0(BLTOUCH, bltouch.high_speed_mode); + EEPROM_WRITE(bltouch_high_speed_mode); + #endif } // @@ -1810,13 +1819,23 @@ void MarlinSettings::postprocess() { // BLTOUCH // { - _FIELD_TEST(bltouch_last_written_mode); + _FIELD_TEST(bltouch_od_5v_mode); #if ENABLED(BLTOUCH) - const bool &bltouch_last_written_mode = bltouch.last_written_mode; + const bool &bltouch_od_5v_mode = bltouch.od_5v_mode; #else - bool bltouch_last_written_mode; + bool bltouch_od_5v_mode; + #endif + EEPROM_READ(bltouch_od_5v_mode); + + #ifdef BLTOUCH_HS_MODE + _FIELD_TEST(bltouch_high_speed_mode); + #if ENABLED(BLTOUCH) + const bool &bltouch_high_speed_mode = bltouch.high_speed_mode; + #else + bool bltouch_high_speed_mode; + #endif + EEPROM_READ(bltouch_high_speed_mode); #endif - EEPROM_READ(bltouch_last_written_mode); } // @@ -2827,11 +2846,11 @@ void MarlinSettings::reset() { TERN_(HAS_PTC, ptc.reset()); // - // BLTOUCH + // BLTouch // - //#if ENABLED(BLTOUCH) - // bltouch.last_written_mode; - //#endif + #ifdef BLTOUCH_HS_MODE + bltouch.high_speed_mode = ENABLED(BLTOUCH_HS_MODE); + #endif // // Kinematic settings From c80ef71c6bd5b3fed36f1b6485d040391a70af70 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 23 Dec 2021 01:05:31 +0000 Subject: [PATCH 07/32] [cron] Bump distribution date (2021-12-23) --- 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 ddabd7b152e7..fac298246f22 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-12-22" +//#define STRING_DISTRIBUTION_DATE "2021-12-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 68cfee56e131..e75f1a178869 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 "2021-12-22" + #define STRING_DISTRIBUTION_DATE "2021-12-23" #endif /** From 1b876c170fc62abbb7381cfa79f2456ab4ec48ac Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 23 Dec 2021 07:49:15 +0100 Subject: [PATCH 08/32] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20settings=20G21=20rep?= =?UTF-8?q?ort=20(#23338)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8a32d4c57ea7..5fda608e3839 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3171,12 +3171,13 @@ void MarlinSettings::reset() { // Announce current units, in case inches are being displayed // CONFIG_ECHO_HEADING("Linear Units"); + CONFIG_ECHO_START(); #if ENABLED(INCH_MODE_SUPPORT) - SERIAL_ECHO_MSG(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); + SERIAL_ECHOPGM(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); #else - SERIAL_ECHO_MSG(" G21 ;"); + SERIAL_ECHOPGM(" G21 ;"); #endif - gcode.say_units(); + gcode.say_units(); // " (in/mm)" // // M149 Temperature units From da67deb621bcf140e2f843c030d2b2b195c39ef9 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 23 Dec 2021 08:32:27 +0100 Subject: [PATCH 09/32] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Fix=20missing=20brac?= =?UTF-8?q?e=20(#23337)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22916 Co-authored-by: Scott Lahteine --- Marlin/src/feature/bltouch.cpp | 16 +++++++++------- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 8 +++++--- buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive | 4 ++-- 4 files changed, 17 insertions(+), 13 deletions(-) diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index d3348e79f0b9..b1cc30bee0d9 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -68,13 +68,15 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else - if (DEBUGGING(LEVELING)) { - PGMSTR(mode0, "OD"); - PGMSTR(mode1, "5V"); - DEBUG_ECHOPGM("BLTouch Mode: "); - DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); - DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); - } + #ifdef DEBUG_OUT + if (DEBUGGING(LEVELING)) { + PGMSTR(mode0, "OD"); + PGMSTR(mode1, "5V"); + DEBUG_ECHOPGM("BLTouch Mode: "); + DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); + } + #endif const bool should_set = od_5v_mode != ENABLED(BLTOUCH_SET_5V_MODE); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 574097863956..38a074eb0128 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -292,7 +292,7 @@ static void _lcd_level_bed_corners_get_next_position() { } while (good_points < nr_edge_points); // loop until all points within tolerance #if ENABLED(BLTOUCH) - if (bltouch.high_speed_mode) + if (bltouch.high_speed_mode) { // In HIGH SPEED MODE do clearance and stow at the very end do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); bltouch.stow(); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 19b3dcbafbbe..4cd43e787aca 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -53,6 +53,8 @@ #include "../../libs/buzzer.h" #endif +#include "../../core/debug_out.h" + #define HAS_DEBUG_MENU ENABLED(LCD_PROGRESS_BAR_TEST) void menu_advanced_settings(); @@ -219,9 +221,9 @@ void menu_advanced_settings(); void bltouch_report() { PGMSTR(mode0, "OD"); PGMSTR(mode1, "5V"); - SERIAL_ECHOPGM("BLTouch Mode: "); - SERIAL_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); - SERIAL_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); + DEBUG_ECHOPGM("BLTouch Mode: "); + DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); char mess[21]; strcpy_P(mess, PSTR("BLTouch Mode: ")); strcpy_P(&mess[15], bltouch.od_5v_mode ? mode1 : mode0); diff --git a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive index 197ece5dfd66..34bf77be27a4 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive +++ b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive @@ -10,8 +10,8 @@ restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT 3 \ EXTRUDERS 8 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 TEMP_SENSOR_5 1 TEMP_SENSOR_6 1 TEMP_SENSOR_7 1 opt_enable SDSUPPORT USB_FLASH_DRIVE_SUPPORT USE_OTG_USB_HOST \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH NEOPIXEL_LED Z_SAFE_HOMING \ - FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH LEVEL_BED_CORNERS LEVEL_CORNERS_USE_PROBE \ + NEOPIXEL_LED Z_SAFE_HOMING FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE # Not necessary to enable auto-fan for all extruders to hit problematic code paths opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_PIN PF13 \ X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2130 \ From 3e737cbc910315364b77af6b1d6d3e92306f48f3 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Thu, 23 Dec 2021 15:19:39 +0700 Subject: [PATCH 10/32] =?UTF-8?q?=F0=9F=94=A7=20Group=20FAST=5FPWM=5FFAN.o?= =?UTF-8?q?ptions=20(#23331)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 3 --- Marlin/Configuration_adv.h | 29 +++++++++++++++------- Marlin/src/inc/Conditionals_post.h | 11 -------- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 1 - 4 files changed, 20 insertions(+), 24 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index bb89bc14a375..c425746bb5d1 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2841,9 +2841,6 @@ // :[1,2,3,4,5,6,7,8] //#define NUM_M106_FANS 1 -// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino -//#define FAST_PWM_FAN - // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency // which is not as annoying as with the hardware PWM. On the other hand, if this frequency // is too low, you should also increment SOFT_PWM_SCALE. diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e50e0cde8954..3eb836ec6562 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -549,18 +549,21 @@ //#define FAN_MAX_PWM 128 /** - * FAST PWM FAN Settings + * Fan Fast PWM * - * Use to change the FAST FAN PWM frequency (if enabled in Configuration.h) - * Combinations of PWM Modes, prescale values and TOP resolutions are used internally to produce a - * frequency as close as possible to the desired frequency. + * Combinations of PWM Modes, prescale values and TOP resolutions are used internally + * to produce a frequency as close as possible to the desired frequency. * - * FAST_PWM_FAN_FREQUENCY [undefined by default] + * FAST_PWM_FAN_FREQUENCY * Set this to your desired frequency. - * If left undefined this defaults to F = F_CPU/(2*255*1) - * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. - * These defaults are the same as with the old FAST_PWM_FAN implementation - no migration is required + * For AVR, if left undefined this defaults to F = F_CPU/(2*255*1) + * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. + * For non AVR, if left undefined this defaults to F = 1Khz. + * This F value is only to protect the hardware from an absence of configuration + * and not to complete it when users are not aware that the frequency must be specifically set to support the target board. + * * NOTE: Setting very low frequencies (< 10 Hz) may result in unexpected timer behavior. + * Setting very high frequencies can damage your hardware. * * USE_OCR2A_AS_TOP [undefined by default] * Boards that use TIMER2 for PWM have limitations resulting in only a few possible frequencies on TIMER2: @@ -570,9 +573,17 @@ * PWM on pin OC2A. Only use this option if you don't need PWM on 0C2A. (Check your schematic.) * USE_OCR2A_AS_TOP sacrifices duty cycle control resolution to achieve this broader range of frequencies. */ +//#define FAST_PWM_FAN // Increase the fan PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino #if ENABLED(FAST_PWM_FAN) - //#define FAST_PWM_FAN_FREQUENCY 31400 + //#define FAST_PWM_FAN_FREQUENCY 31400 // Define here to override the defaults below //#define USE_OCR2A_AS_TOP + #ifndef FAST_PWM_FAN_FREQUENCY + #ifdef __AVR__ + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) + #else + #define FAST_PWM_FAN_FREQUENCY 1000U + #endif + #endif #endif /** diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 7fb839550671..95c8f7737b31 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2667,17 +2667,6 @@ #error "FAN_OFF_PWM must be less than or equal to FAN_MIN_PWM." #endif -/** - * FAST PWM FAN default PWM frequency - */ -#if !defined(FAST_PWM_FAN_FREQUENCY) && ENABLED(FAST_PWM_FAN) - #ifdef __AVR__ - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) - #else - #define FAST_PWM_FAN_FREQUENCY 1000U - #endif -#endif - /** * Controller Fan Settings */ diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index c6f1e014e076..15c6955a83a8 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -95,7 +95,6 @@ #define FAN_MAX_PWM 255 #else #define FAST_PWM_FAN // STM32 Variant allow TIMER2 Hardware PWM - #define FAST_PWM_FAN_FREQUENCY 31400 // This frequency allow a good range, fan starts at 3%, half noise at 50% #define FAN_MIN_PWM 5 #define FAN_MAX_PWM 255 #endif From df9eb566c763be34f4c7ed51fc7526a840df860d Mon Sep 17 00:00:00 2001 From: MrAlvin Date: Thu, 23 Dec 2021 10:47:52 +0100 Subject: [PATCH 11/32] =?UTF-8?q?=F0=9F=9A=B8=20Show=20mm'ss=20during=20fi?= =?UTF-8?q?rst=20hour=20(#23335)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/libs/duration_t.h | 28 +++++++++++++++++----------- 1 file changed, 17 insertions(+), 11 deletions(-) diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 2528bcdbff89..df2c9cd099c1 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -127,11 +127,11 @@ struct duration_t { * 59s */ char* toString(char * const buffer) const { - int y = this->year(), - d = this->day() % 365, - h = this->hour() % 24, - m = this->minute() % 60, - s = this->second() % 60; + const uint16_t y = this->year(), + d = this->day() % 365, + h = this->hour() % 24, + m = this->minute() % 60, + s = this->second() % 60; if (y) sprintf_P(buffer, PSTR("%iy %id %ih %im %is"), y, d, h, m, s); else if (d) sprintf_P(buffer, PSTR("%id %ih %im %is"), d, h, m, s); @@ -149,23 +149,29 @@ struct duration_t { * * Output examples: * 123456789 (strlen) + * 12'34 * 99:59 * 11d 12:33 */ uint8_t toDigital(char *buffer, bool with_days=false) const { - uint16_t h = uint16_t(this->hour()), - m = uint16_t(this->minute() % 60UL); + const uint16_t h = uint16_t(this->hour()), + m = uint16_t(this->minute() % 60UL); if (with_days) { - uint16_t d = this->day(); - sprintf_P(buffer, PSTR("%hud %02hu:%02hu"), d, h % 24, m); + const uint16_t d = this->day(); + sprintf_P(buffer, PSTR("%hud %02hu:%02hu"), d, h % 24, m); // 1d 23:45 return d >= 10 ? 9 : 8; } + else if (!h) { + const uint16_t s = uint16_t(this->second() % 60UL); + sprintf_P(buffer, PSTR("%02hu'%02hu"), m, s); // 12'34 + return 5; + } else if (h < 100) { - sprintf_P(buffer, PSTR("%02hu:%02hu"), h, m); + sprintf_P(buffer, PSTR("%02hu:%02hu"), h, m); // 12:34 return 5; } else { - sprintf_P(buffer, PSTR("%hu:%02hu"), h, m); + sprintf_P(buffer, PSTR("%hu:%02hu"), h, m); // 123:45 return 6; } } From ca0215ba646e410e4828ebf14c86e75fc8765eeb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 24 Dec 2021 01:04:40 +0000 Subject: [PATCH 12/32] [cron] Bump distribution date (2021-12-24) --- 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 fac298246f22..8dc516a329b2 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-12-23" +//#define STRING_DISTRIBUTION_DATE "2021-12-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e75f1a178869..df523fb3891b 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 "2021-12-23" + #define STRING_DISTRIBUTION_DATE "2021-12-24" #endif /** From 80a537cd13f386fe8140ca672c4aa51d597d5e21 Mon Sep 17 00:00:00 2001 From: Attila BODY Date: Fri, 24 Dec 2021 06:57:20 +0100 Subject: [PATCH 13/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Robin=20Nano=20v3=20?= =?UTF-8?q?filament=20runout=20pins=20(#23344)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/pins/mega/pins_OVERLORD.h | 2 +- Marlin/src/pins/pins_postprocess.h | 7 +++++-- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 1 - Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 6 ++---- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 6 ++---- Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 4 ++-- 7 files changed, 13 insertions(+), 15 deletions(-) diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 0884d8ecb514..98f8da571940 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -49,7 +49,7 @@ #define Z_MIN_PROBE_PIN 46 // JP4, Tfeed1 #endif -#if ENABLED(FILAMENT_RUNOUT_SENSOR) +#ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN 44 // JP3, Tfeed2 #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 1e6703fd4a3a..fe8c4c6c41aa 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -546,14 +546,17 @@ #undef K_MAX_PIN #endif -// Filament Sensor first pin alias #if HAS_FILAMENT_SENSOR - #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN + #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN // Filament Sensor first pin alias #else #undef FIL_RUNOUT_PIN #undef FIL_RUNOUT1_PIN #endif +#if NUM_RUNOUT_SENSORS < 2 + #undef FIL_RUNOUT2_PIN +#endif + #ifndef LCD_PINS_D4 #define LCD_PINS_D4 -1 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 79ac308ce71c..0a94a582d43c 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -134,7 +134,6 @@ #define FAN_PIN 9 #define FAN1_PIN 12 -#define NUM_RUNOUT_SENSORS 2 #define FIL_RUNOUT_PIN 22 #define FIL_RUNOUT2_PIN 21 diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 5e612d3e8c22..65ecd37e62da 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -121,10 +121,8 @@ #define Z_MIN_PROBE_PIN 49 #endif -#if HAS_FILAMENT_SENSOR - #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN Y_MIN_PIN - #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN Y_MIN_PIN #endif // diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 37a76c527821..76a2d5a3985f 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -109,10 +109,8 @@ #define Z_MIN_PROBE_PIN 49 #endif -#if HAS_FILAMENT_SENSOR - #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN Y_MIN_PIN - #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN Y_MIN_PIN #endif // diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 1b37940e2a0a..a450515a79ff 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -68,7 +68,7 @@ #if SERVO0_PIN == BEEPER_PIN #undef BEEPER_PIN #endif -#elif ENABLED(FILAMENT_RUNOUT_SENSOR) +#elif HAS_FILAMENT_SENSOR #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN 27 #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h index c2dea50b2988..bbf162bb0d98 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -145,10 +145,10 @@ #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN MT_DET_1_PIN + #define FIL_RUNOUT_PIN PA4 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN MT_DET_2_PIN + #define FIL_RUNOUT2_PIN PE6 #endif #ifndef POWER_LOSS_PIN From 21cd71550663f46c361e6798c04ebcc0165391f3 Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Fri, 24 Dec 2021 14:03:32 +0800 Subject: [PATCH 14/32] =?UTF-8?q?=E2=9C=A8=20MKS=20TinyBee=20board=20suppo?= =?UTF-8?q?rt=20(#23340)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: Sola <42537573+solawc@users.noreply.github.com> --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 207 +++++++++++++++++++++++ Marlin/src/pins/pins.h | 2 + ini/esp32.ini | 5 + 4 files changed, 215 insertions(+) create mode 100644 Marlin/src/pins/esp32/pins_MKS_TINYBEE.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 674d203027dd..aee9b3c49287 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -433,6 +433,7 @@ #define BOARD_FYSETC_E4 6005 // FYSETC E4 #define BOARD_PANDA_ZHU 6006 // Panda_ZHU #define BOARD_PANDA_M4 6007 // Panda_M4 +#define BOARD_MKS_TINYBEE 6008 // MKS TinyBee based on ESP32 (with I2S stepper stream) // // SAMD51 ARM Cortex M4 diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h new file mode 100644 index 000000000000..bfa38adadf73 --- /dev/null +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -0,0 +1,207 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * MRR ESPE pin assignments + * MRR ESPE is a 3D printer control board based on the ESP32 microcontroller. + * Supports 5 stepper drivers (using I2S stepper stream), heated bed, + * single hotend, and LCD controller. + */ + +#include "env_validate.h" + +#if EXTRUDERS > 2 || E_STEPPERS > 2 + #error "MKS ESP Nano only supports two E Steppers. Comment out this line to continue." +#elif HOTENDS > 2 + #error "MKS ESP Nano only supports two hotend / E-stepper. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "MKS TinyBee" +#define BOARD_WEBSITE_URL "https://github.com/makerbase-mks" +#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME + +// +// Servos +// +#define SERVO0_PIN 2 + +// +// Limit Switches +// +#define X_STOP_PIN 33 +#define Y_STOP_PIN 32 +#define Z_STOP_PIN 22 +//#define FIL_RUNOUT_PIN 35 + +// +// Enable I2S stepper stream +// +#define I2S_STEPPER_STREAM +#if ENABLED(I2S_STEPPER_STREAM) + #define I2S_WS 26 + #define I2S_BCK 25 + #define I2S_DATA 27 + #if ENABLED(LIN_ADVANCE) + #error "I2S stream is currently incompatible with LIN_ADVANCE." + #endif +#endif + +// +// Steppers +// +#define X_STEP_PIN 129 +#define X_DIR_PIN 130 +#define X_ENABLE_PIN 128 + +#define Y_STEP_PIN 132 +#define Y_DIR_PIN 133 +#define Y_ENABLE_PIN 131 + +#define Z_STEP_PIN 135 +#define Z_DIR_PIN 136 +#define Z_ENABLE_PIN 134 + +#define E0_STEP_PIN 138 +#define E0_DIR_PIN 139 +#define E0_ENABLE_PIN 137 + +#define E1_STEP_PIN 141 +#define E1_DIR_PIN 142 +#define E1_ENABLE_PIN 140 + +#define Z2_STEP_PIN 141 +#define Z2_DIR_PIN 142 +#define Z2_ENABLE_PIN 140 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_1_PIN 34 // Analog Input, you need set R6=0Ω and R7=NC +#define TEMP_BED_PIN 39 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 145 +#define HEATER_1_PIN 146 +#define FAN_PIN 147 +#define FAN1_PIN 148 +#define HEATER_BED_PIN 144 + +//#define CONTROLLER_FAN_PIN 148 +//#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 + +// +// MicroSD card +// +#define SD_MOSI_PIN 23 +#define SD_MISO_PIN 19 +#define SD_SCK_PIN 18 +#define SDSS 5 +#define SD_DETECT_PIN 34 // IO34 default is SD_DET signal(Jump to SDDET) +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers + +/** + * ------ ------ + * (BEEPER) 149 |10 9 | 13 (BTN_ENC) (SPI MISO) 19 |10 9 | 18 (SPI SCK) + * (LCD_EN) 21 | 8 7 | 4 (LCD_RS) (BTN_EN1) 14 | 8 7 | 5 (SPI CS) + * (LCD_D4) 0 | 6 5 16 (LCD_D5) (BTN_EN2) 12 | 6 5 23 (SPI MOSI) + * (LCD_D6) 15 | 4 3 | 17 (LCD_D7) (SPI_DET) 34 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ + +#define EXP1_03_PIN 17 +#define EXP1_04_PIN 15 +#define EXP1_05_PIN 16 +#define EXP1_06_PIN 0 +#define EXP1_07_PIN 4 +#define EXP1_08_PIN 21 +#define EXP1_09_PIN 13 +#define EXP1_10_PIN 149 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN 34 +#define EXP2_05_PIN 23 +#define EXP2_06_PIN 12 +#define EXP2_07_PIN 5 +#define EXP2_08_PIN 14 +#define EXP2_09_PIN 18 +#define EXP2_10_PIN 19 + +#if HAS_WIRED_LCD + + #define BEEPER_PIN 149 + #define BTN_ENC 13 + #define LCD_PINS_ENABLE 21 + #define LCD_PINS_RS 4 + #define BTN_EN1 14 + #define BTN_EN2 12 + #define LCD_BACKLIGHT_PIN -1 + + // 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 15 + #define DOGLCD_CS 16 + //#define DOGLCD_SCK 19 + //#define DOGLCD_MOSI 23 + + // Required for MKS_MINI_12864 with this board + //#define MKS_LCD12864B + + #elif ENABLED(MKS_MINI_12864_V3) + + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_09_PIN + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 0 + #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #define LCD_PINS_D5 16 + #define LCD_PINS_D6 15 + #define LCD_PINS_D7 17 + #endif + + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 54967197f067..0f0f42508db0 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -711,6 +711,8 @@ #include "esp32/pins_PANDA_ZHU.h" // ESP32 env:PANDA #elif MB(PANDA_M4) #include "esp32/pins_PANDA_M4.h" // ESP32 env:PANDA +#elif MB(MKS_TINYBEE) + #include "esp32/pins_MKS_TINYBEE.h" // ESP32 env:mks_tinybee // // Adafruit Grand Central M4 (SAMD51 ARM Cortex-M4) diff --git a/ini/esp32.ini b/ini/esp32.ini index 9c0c44db67b9..0815486cc993 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -37,3 +37,8 @@ lib_deps = ${common.lib_deps} board_build.partitions = Marlin/src/HAL/ESP32/esp32.csv upload_speed = 115200 monitor_speed = 115200 + +[env:mks_tinybee] +extends = env:esp32 +platform = espressif32@2.1.0 +board_build.partitions = default_8MB.csv From d5dff1948d900ce6fdec31e3f839e905ba09a46b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 01:46:51 -0600 Subject: [PATCH 15/32] =?UTF-8?q?=F0=9F=94=A7=20Sanity=20check=20MMU2=5FME?= =?UTF-8?q?NUS?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index fbc0e3d1f04d..c8ac48f7cff5 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1070,7 +1070,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif ENABLED(MMU_EXTRUDER_SENSOR) && DISABLED(FILAMENT_RUNOUT_SENSOR) #error "MMU_EXTRUDER_SENSOR requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." #elif ENABLED(MMU_EXTRUDER_SENSOR) && !HAS_LCD_MENU - #error "MMU_EXTRUDER_SENSOR requires an LCD supporting MarlinUI to be enabled." + #error "MMU_EXTRUDER_SENSOR requires an LCD supporting MarlinUI." + #elif ENABLED(MMU2_MENUS) && !HAS_LCD_MENU + #error "MMU2_MENUS requires an LCD supporting MarlinUI." #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(S) / HAS_EXTENDABLE_MMU(S)."); #endif From 6d09d1d7fb2ce06dfe2693d841e3d417fd33c1b2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 25 Dec 2021 01:04:01 +0000 Subject: [PATCH 16/32] [cron] Bump distribution date (2021-12-25) --- 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 8dc516a329b2..596e910a1f61 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-12-24" +//#define STRING_DISTRIBUTION_DATE "2021-12-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index df523fb3891b..b43547ef53c1 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 "2021-12-24" + #define STRING_DISTRIBUTION_DATE "2021-12-25" #endif /** From cd1920b35057ee21c77f568af996434303122494 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 20:59:28 -0600 Subject: [PATCH 17/32] =?UTF-8?q?=F0=9F=94=A8=20Ignore=20cmake=20generated?= =?UTF-8?q?=20build=20folder?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 2b40149b5f50..0af55339d8aa 100755 --- a/.gitignore +++ b/.gitignore @@ -155,6 +155,7 @@ spi_flash.bin CMakeLists.txt src/CMakeLists.txt CMakeListsPrivate.txt +build/ # CLion cmake-build-* From 532f21f96f421e485b472025de2cde9677999179 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 21:32:00 -0600 Subject: [PATCH 18/32] =?UTF-8?q?=F0=9F=94=A8=20Ignore=20sublime=20workspa?= =?UTF-8?q?ce=20file?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 0af55339d8aa..72fd117bd234 100755 --- a/.gitignore +++ b/.gitignore @@ -25,6 +25,7 @@ bdf2u8g marlin_config.json mczip.h *.gen +*.sublime-workspace # # OS From e211ff148c39bf5dace72de7cffbb83f19d3f1bf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 21:33:59 -0600 Subject: [PATCH 19/32] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20HAL=20as?= =?UTF-8?q?=20singleton=20(#23295)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL.cpp | 14 +- Marlin/src/HAL/AVR/HAL.h | 170 +++++++++++++-------- Marlin/src/HAL/AVR/MarlinSerial.cpp | 4 +- Marlin/src/HAL/AVR/fast_pwm.cpp | 11 +- Marlin/src/HAL/AVR/timers.h | 4 +- Marlin/src/HAL/DUE/HAL.cpp | 45 ++---- Marlin/src/HAL/DUE/HAL.h | 132 ++++++++++------ Marlin/src/HAL/DUE/MarlinSerial.cpp | 4 +- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/HAL.cpp | 35 +++-- Marlin/src/HAL/ESP32/HAL.h | 142 ++++++++++------- Marlin/src/HAL/ESP32/timers.h | 4 +- Marlin/src/HAL/LINUX/HAL.cpp | 39 ++--- Marlin/src/HAL/LINUX/HAL.h | 145 ++++++++++++------ Marlin/src/HAL/LINUX/arduino.cpp | 4 +- Marlin/src/HAL/LINUX/include/Arduino.h | 5 +- Marlin/src/HAL/LINUX/timers.h | 4 +- Marlin/src/HAL/LPC1768/HAL.cpp | 42 +++-- Marlin/src/HAL/LPC1768/HAL.h | 160 ++++++++++++------- Marlin/src/HAL/LPC1768/Servo.h | 3 +- Marlin/src/HAL/LPC1768/fast_pwm.cpp | 14 +- Marlin/src/HAL/LPC1768/main.cpp | 6 +- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 173 +++++++++++++-------- Marlin/src/HAL/NATIVE_SIM/timers.h | 4 +- Marlin/src/HAL/SAMD51/HAL.cpp | 26 ++-- Marlin/src/HAL/SAMD51/HAL.h | 125 +++++++++------ Marlin/src/HAL/STM32/HAL.cpp | 28 ++-- Marlin/src/HAL/STM32/HAL.h | 179 ++++++++++++---------- Marlin/src/HAL/STM32/HAL_SPI.cpp | 8 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 8 +- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 +- Marlin/src/HAL/STM32/pinsDebug.h | 6 +- Marlin/src/HAL/STM32/timers.h | 4 +- Marlin/src/HAL/STM32F1/HAL.cpp | 190 +++++++++++------------ Marlin/src/HAL/STM32F1/HAL.h | 184 ++++++++++++---------- Marlin/src/HAL/STM32F1/Servo.h | 3 +- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 8 +- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.cpp | 79 +++++----- Marlin/src/HAL/TEENSY31_32/HAL.h | 131 +++++++++++----- Marlin/src/HAL/TEENSY31_32/timers.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.cpp | 110 +++++++------- Marlin/src/HAL/TEENSY35_36/HAL.h | 133 +++++++++++----- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.cpp | 194 ++++++++++++------------ Marlin/src/HAL/TEENSY40_41/HAL.h | 148 ++++++++++++------ Marlin/src/HAL/TEENSY40_41/timers.h | 2 +- Marlin/src/HAL/shared/HAL.cpp | 36 +++++ Marlin/src/HAL/shared/HAL_spi_L6470.cpp | 8 +- Marlin/src/MarlinCore.cpp | 48 +++--- Marlin/src/feature/caselight.cpp | 2 +- Marlin/src/feature/controllerfan.cpp | 2 +- Marlin/src/feature/e_parser.h | 4 +- Marlin/src/feature/leds/leds.cpp | 2 +- Marlin/src/feature/spindle_laser.cpp | 10 +- Marlin/src/feature/spindle_laser.h | 2 +- Marlin/src/gcode/control/M42.cpp | 4 +- Marlin/src/gcode/gcode_d.cpp | 10 +- Marlin/src/inc/SanityCheck.h | 7 + Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 4 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/servo.cpp | 2 +- Marlin/src/module/servo.h | 2 +- Marlin/src/module/stepper.cpp | 10 +- Marlin/src/module/temperature.cpp | 112 +++++++------- ini/native.ini | 4 +- 69 files changed, 1756 insertions(+), 1267 deletions(-) create mode 100644 Marlin/src/HAL/shared/HAL.cpp diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index d7bf2a6f6fbb..2b6d2bdbcf07 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -36,7 +36,7 @@ // ------------------------ // Don't initialize/override variable (which would happen in .init4) -uint8_t reset_reason __attribute__((section(".noinit"))); +uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); // ------------------------ // Public functions @@ -45,22 +45,22 @@ uint8_t reset_reason __attribute__((section(".noinit"))); __attribute__((naked)) // Don't output function pro- and epilogue __attribute__((used)) // Output the function, even if "not used" __attribute__((section(".init3"))) // Put in an early user definable section -void HAL_save_reset_reason() { +void save_reset_reason() { #if ENABLED(OPTIBOOT_RESET_REASON) __asm__ __volatile__( A("STS %0, r2") - : "=m"(reset_reason) + : "=m"(hal.reset_reason) ); #else - reset_reason = MCUSR; + hal.reset_reason = MCUSR; #endif // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop - MCUSR = 0; + hal.clear_reset_source(); wdt_disable(); } -void HAL_init() { +void MarlinHAL::init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 @@ -77,7 +77,7 @@ void HAL_init() { #endif } -void HAL_reboot() { +void MarlinHAL::reboot() { #if ENABLED(USE_WATCHDOG) while (1) { /* run out the watchdog */ } #else diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 2217f239d64e..9babe2d60352 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -74,9 +74,8 @@ #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END() SREG = _sreg #endif -#define ISRS_ENABLED() TEST(SREG, SREG_I) -#define ENABLE_ISRS() sei() -#define DISABLE_ISRS() cli() + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment // ------------------------ // Types @@ -84,16 +83,16 @@ typedef int8_t pin_t; +// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo + +class Servo; +typedef Servo hal_servo_t; // ------------------------ -// Public Variables +// Serial ports // ------------------------ -extern uint8_t reset_reason; - -// Serial ports #ifdef USBCON #include "../../core/serial_hook.h" typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; @@ -142,20 +141,31 @@ extern uint8_t reset_reason; #endif #endif -// ------------------------ -// Public functions -// ------------------------ +// +// ADC +// +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 -void HAL_init(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -//void cli(); +#define HAL_SENSITIVE_PINS 0, 1, -//void _delay_ms(const int delay); +#ifdef __AVR_AT90USB1286__ + #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) +#endif -inline void HAL_clear_reset_source() { } -inline uint8_t HAL_get_reset_source() { return reset_reason; } +// AVR compatibility +#define strtof strtod -void HAL_reboot(); +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -166,63 +176,89 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC -#ifdef DIDR2 - #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0) -#else - #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind); -#endif +// ------------------------ +// MarlinHAL Class +// ------------------------ -inline void HAL_adc_init() { - ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; - DIDR0 = 0; - #ifdef DIDR2 - DIDR2 = 0; - #endif -} +class MarlinHAL { +public: -#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC) -#ifdef MUX5 - #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch) -#else - #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch) -#endif + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 -#define HAL_READ_ADC() ADC -#define HAL_ADC_READY() !TEST(ADCSRA, ADSC) + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + static inline bool isr_state() { return TEST(SREG, SREG_I); } + static inline void isr_on() { sei(); } + static inline void isr_off() { cli(); } -#define HAL_SENSITIVE_PINS 0, 1, + static inline void delay_ms(const int ms) { _delay_ms(ms); } -#ifdef __AVR_AT90USB1286__ - #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) -#endif + // Tasks, called from idle() + static inline void idletask() {} -// AVR compatibility -#define strtof strtod + // Reset + static uint8_t reset_reason; + static inline uint8_t get_reset_source() { return reset_reason; } + static inline void clear_reset_source() { MCUSR = 0; } -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + // Free SRAM + static inline int freeMemory() { return freeMemory(); } -/** - * set_pwm_frequency - * Sets the frequency of the timer corresponding to the provided pin - * as close as possible to the provided desired frequency. Internally - * calculates the required waveform generation mode, prescaler and - * resolution values required and sets the timer registers accordingly. - * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) - * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) - */ -void set_pwm_frequency(const pin_t pin, int f_desired); + // + // ADC Methods + // -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + // Called by Temperature::init once at startup + static inline void adc_init() { + ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; + DIDR0 = 0; + #ifdef DIDR2 + DIDR2 = 0; + #endif + } + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const uint8_t ch) { + #ifdef DIDR2 + if (ch > 7) { SBI(DIDR2, ch & 0x07); return; } + #endif + SBI(DIDR0, ch); + } + + // Begin ADC sampling on the given channel + static inline void adc_start(const pin_t ch) { + #ifdef MUX5 + if (ch > 7) { ADCSRB = _BV(MUX5); return; } + #endif + ADCSRB = 0; + ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC); + } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); } + + // The current value of the ADC register + static inline __typeof__(ADC) adc_value() { return ADC; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin as close as + * possible to the provided desired frequency. Internally calculate + * the required waveform generation mode, prescaler, and resolution + * values and set timer registers accordingly. + * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) + * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index cd8bf5e6903b..986462437c8f 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -486,7 +486,7 @@ void MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -534,7 +534,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !B_TXC) { diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 804e5fad3070..0053b44c3c7b 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -35,10 +35,9 @@ struct Timer { }; /** - * get_pwm_timer - * Get the timer information and register of the provided pin. - * Return a Timer struct containing this information. - * Used by set_pwm_frequency, set_pwm_duty + * Get the timer information and register for a pin. + * Return a Timer struct containing this information. + * Used by set_pwm_frequency, set_pwm_duty */ Timer get_pwm_timer(const pin_t pin) { uint8_t q = 0; @@ -150,7 +149,7 @@ Timer get_pwm_timer(const pin_t pin) { return timer; } -void set_pwm_frequency(const pin_t pin, int f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { Timer timer = get_pwm_timer(pin); if (timer.n == 0) return; // Don't proceed if protected timer or not recognized uint16_t size; @@ -230,7 +229,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { #endif // NEEDS_HARDWARE_PWM -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { #if NEEDS_HARDWARE_PWM // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 36b04eae0d1f..e1fcbf52d6d8 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP /* 18 cycles maximum latency */ #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index a3985652e71d..20b711b1b05e 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -34,7 +34,7 @@ // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Public functions @@ -42,8 +42,7 @@ uint16_t HAL_adc_result; TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -// HAL initialization task -void HAL_init() { +void MarlinHAL::init() { // Initialize the USB stack #if ENABLED(SDSUPPORT) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up @@ -52,21 +51,17 @@ void HAL_init() { TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } -// HAL idle task -void HAL_idletask() { - // Perform USB stack housekeeping - usb_task_idle(); +void MarlinHAL::init_board() { + #ifdef BOARD_INIT + BOARD_INIT(); + #endif } -// Disable interrupts -void cli() { noInterrupts(); } - -// Enable interrupts -void sei() { interrupts(); } - -void HAL_clear_reset_source() { } +void MarlinHAL::idletask() { + usb_task_idle(); // Perform USB stack housekeeping +} -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { switch ((RSTC->RSTC_SR >> 8) & 0x07) { case 0: return RST_POWER_ON; case 1: return RST_BACKUP; @@ -77,12 +72,7 @@ uint8_t HAL_get_reset_source() { } } -void HAL_reboot() { rstc_start_software_reset(RSTC); } - -void _delay_ms(const int delay_ms) { - // Todo: port for Due? - delay(delay_ms); -} +void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -94,19 +84,6 @@ int freeMemory() { return (int)&free_memory - (heap_end ?: (int)&_ebss); } -// ------------------------ -// ADC -// ------------------------ - -void HAL_adc_start_conversion(const uint8_t ch) { - HAL_adc_result = analogRead(ch); -} - -uint16_t HAL_adc_get_result() { - // nop - return HAL_adc_result; -} - // Forward the default serial ports #if USING_HW_SERIAL0 DefaultSerial1 MSerial0(false, Serial); diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 96ab5d9808ac..0dd123acdd51 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -38,6 +38,10 @@ #include "../../core/serial_hook.h" +// ------------------------ +// Serial ports +// ------------------------ + typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; @@ -97,35 +101,31 @@ extern DefaultSerial4 MSerial3; #include "MarlinSerial.h" #include "MarlinSerialUSB.h" -// On AVR this is in math.h? -#define square(x) ((x)*(x)) +// ------------------------ +// Types +// ------------------------ typedef int8_t pin_t; +// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +class Servo; +typedef Servo hal_servo_t; // // Interrupts // -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() - -void cli(); // Disable interrupts -void sei(); // Enable interrupts - -void HAL_clear_reset_source(); // clear reset reason -uint8_t HAL_get_reset_source(); // get reset reason +#define sei() noInterrupts() +#define cli() interrupts() -void HAL_reboot(); +#define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off() +#define CRITICAL_SECTION_END() if (_irqon) hal.isr_on() // // ADC // -extern uint16_t HAL_adc_result; // result of last ADC conversion +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) @@ -133,24 +133,8 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion #define HAL_ANALOG_SELECT(ch) -inline void HAL_adc_init() {}//todo - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); - // -// PWM -// -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// -// Pin Map +// Pin Mapping for M42, M43, M226 // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -159,27 +143,18 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -void HAL_idletask(); -void HAL_init(); - -// -// Utility functions -// -void _delay_ms(const int delay); +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif -int freeMemory(); - #pragma GCC diagnostic pop #ifdef __cplusplus @@ -189,3 +164,70 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s #ifdef __cplusplus } #endif + +// Return free RAM between end of heap (or end bss) and whatever is current +int freeMemory(); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Software reset + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static inline void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const int ch) {} + + // Begin ADC sampling on the given channel + static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static inline uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No inverting the duty cycle in this HAL. + * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index fe62ff5607d5..638f7a100722 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -406,7 +406,7 @@ size_t MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -454,7 +454,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) { diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index e2932ff36f91..bcfd07e268c5 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 810e386894ec..604acae8dd5b 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -52,7 +52,7 @@ // Externs // ------------------------ -portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; +portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; // ------------------------ // Local defines @@ -64,7 +64,7 @@ portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Private Variables @@ -95,20 +95,22 @@ volatile int numPWMUsed = 0, #endif #if ENABLED(USE_ESP32_EXIO) + HardwareSerial YSerial2(2); void Write_EXIO(uint8_t IO, uint8_t v) { - if (ISRS_ENABLED()) { - DISABLE_ISRS(); + if (hal.isr_state()) { + hal.isr_off(); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); - ENABLE_ISRS(); + hal.isr_on(); } else YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); } + #endif -void HAL_init_board() { +void MarlinHAL::init_board() { #if ENABLED(USE_ESP32_TASK_WDT) esp_task_wdt_init(10, true); #endif @@ -154,27 +156,24 @@ void HAL_init_board() { #endif } -void HAL_idletask() { +void MarlinHAL::idletask() { #if BOTH(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); } -void HAL_clear_reset_source() { } - -uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } +uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } -void HAL_reboot() { ESP.restart(); } - -void _delay_ms(int delay_ms) { delay(delay_ms); } +void MarlinHAL::reboot() { ESP.restart(); } // return free memory between end of heap (or end bss) and whatever is current -int freeMemory() { return ESP.getFreeHeap(); } +int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } // ------------------------ // ADC // ------------------------ + #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL adc1_channel_t get_channel(int pin) { @@ -196,7 +195,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) { } } -void HAL_adc_init() { +void MarlinHAL::adc_init() { // Configure ADC adc1_config_width(ADC_WIDTH_12Bit); @@ -226,11 +225,11 @@ void HAL_adc_init() { } } -void HAL_adc_start_conversion(const uint8_t adc_pin) { - const adc1_channel_t chan = get_channel(adc_pin); +void MarlinHAL::adc_start(const pin_t pin) { + const adc1_channel_t chan = get_channel(pin); uint32_t mv; esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); - HAL_adc_result = mv * 1023.0 / 3300.0; + adc_result = mv * 1023.0 / 3300.0; // Change the attenuation level based on the new reading adc_atten_t atten; diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 8473e3c4e469..361c9032317d 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -49,8 +49,6 @@ // Defines // ------------------------ -extern portMUX_TYPE spinlock; - #define MYSERIAL1 flushableSerial #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -65,9 +63,6 @@ extern portMUX_TYPE spinlock; #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) -#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL) -#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock) -#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock) // ------------------------ // Types @@ -75,14 +70,8 @@ extern portMUX_TYPE spinlock; typedef int16_t pin_t; -#define HAL_SERVO_LIB Servo - -// ------------------------ -// Public Variables -// ------------------------ - -/** result of last ADC conversion */ -extern uint16_t HAL_adc_result; +class Servo; +typedef Servo hal_servo_t; // ------------------------ // Public functions @@ -91,59 +80,21 @@ extern uint16_t HAL_adc_result; // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// clear reset reason -void HAL_clear_reset_source(); - -// reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(int delay); - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - void analogWrite(pin_t pin, int value); // ADC #define HAL_ANALOG_SELECT(pin) -void HAL_adc_init(); - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// Pin Map +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -#define BOARD_INIT() HAL_init_board(); -void HAL_idletask(); -inline void HAL_init() {} -void HAL_init_board(); - #if ENABLED(USE_ESP32_EXIO) void Write_EXIO(uint8_t IO, uint8_t v); #endif @@ -188,3 +139,86 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) { } } + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +void _delay_ms(const int ms); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static inline void init() {} // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Restart the firmware + + static portMUX_TYPE spinlock; + static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; } + static inline void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); } + static inline void isr_off() { portENTER_CRITICAL(&spinlock); } + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} + + // Free SRAM + static int freeMemory(); + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const pin_t pin) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static inline uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No inverting the duty cycle in this HAL. + * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 266169848daf..efae594f6cd8 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -136,5 +136,5 @@ 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); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index 0b679170ef17..91739aaa7b06 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -24,6 +24,12 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" +extern MarlinHAL hal; + +// ------------------------ +// Serial ports +// ------------------------ + MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); // U8glib required functions @@ -37,42 +43,21 @@ extern "C" { //************************// // return free heap space -int freeMemory() { - return 0; -} +int freeMemory() { return 0; } // ------------------------ // ADC // ------------------------ -void HAL_adc_init() { +uint8_t MarlinHAL::active_ch = 0; -} - -void HAL_adc_enable_channel(const uint8_t ch) { - -} - -uint8_t active_ch = 0; -void HAL_adc_start_conversion(const uint8_t ch) { - active_ch = ch; -} - -bool HAL_adc_finished() { - return true; -} - -uint16_t HAL_adc_get_result() { - pin_t pin = analogInputToDigitalPin(active_ch); +uint16_t MarlinHAL::adc_value() { + const pin_t pin = analogInputToDigitalPin(active_ch); if (!VALID_PIN(pin)) return 0; - uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); + const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); return data; // return 10bit value as Marlin expects } -void HAL_pwm_init() { - -} - -void HAL_reboot() { /* Reset the application state and GPIO */ } +void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index d7d3a92b73b9..0bd8635c9045 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -21,25 +21,42 @@ */ #pragma once -#define CPU_32_BIT - -#define F_CPU 100000000UL -#define SystemCoreClock F_CPU #include #include #include - #undef min #undef max - #include -void _printf (const char *format, ...); +#include "hardware/Clock.h" + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +// ------------------------ +// Defines +// ------------------------ + +#define CPU_32_BIT +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +#define F_CPU 100000000UL +#define SystemCoreClock F_CPU + +#define DELAY_CYCLES(x) Clock::delayCycles(x) + +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +void _printf(const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); -//extern "C" volatile uint32_t _millis; - //arduino: Print.h #define DEC 10 #define HEX 16 @@ -49,36 +66,28 @@ uint8_t _getc(); #define B01 1 #define B10 2 -#include "hardware/Clock.h" - -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" -#include "fastio.h" -#include "watchdog.h" -#include "serial.h" - -#define SHARED_SERVOS HAS_SERVOS +// ------------------------ +// Serial ports +// ------------------------ extern MSerialT usb_serial; #define MYSERIAL1 usb_serial -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // // Interrupts // #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() -#define ISRS_ENABLED() -#define ENABLE_ISRS() -#define DISABLE_ISRS() -inline void HAL_init() {} +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) + +// ------------------------ +// Class Utilities +// ------------------------ -// Utility functions #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -88,29 +97,67 @@ int freeMemory(); #pragma GCC diagnostic pop -// ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Reset the application state and GPIO + + static inline bool isr_state() { return true; } + static inline void isr_on() {} + static inline void isr_off() {} + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static inline void idletask() {} + + // Reset + static constexpr uint8_t reset_reason = RST_POWER_ON; + static inline uint8_t get_reset_source() { return reset_reason; } + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint8_t active_ch; + + // Called by Temperature::init once at startup + static inline void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const uint8_t) {} + + // Begin ADC sampling on the given channel + static inline void adc_start(const pin_t ch) { active_ch = ch; } -void HAL_adc_init(); -void HAL_adc_enable_channel(const uint8_t ch); -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // The current value of the ADC register + static uint16_t adc_value(); -// Reset source -inline void HAL_clear_reset_source(void) {} -inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to change the resolution or invert the duty cycle. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } -void HAL_reboot(); // Reset the application state and GPIO + static inline void set_pwm_frequency(const pin_t, int) {} +}; -/* ---------------- Delay in cycles */ -FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { - Clock::delayCycles(x); -} +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 4b56d02a389c..075b4ccde2f4 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -31,9 +31,7 @@ void cli() { } // Disable void sei() { } // Enable // Time functions -void _delay_ms(const int delay_ms) { - delay(delay_ms); -} +void _delay_ms(const int ms) { delay(ms); } uint32_t millis() { return (uint32_t)Clock::millis(); diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index d4086e259a2f..49e04d0cb7d3 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -59,7 +59,6 @@ typedef uint8_t byte; #endif #define sq(v) ((v) * (v)) -#define square(v) sq(v) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) //Interrupts @@ -74,8 +73,8 @@ extern "C" { } // Time functions -extern "C" void delay(const int milis); -void _delay_ms(const int delay); +extern "C" void delay(const int ms); +void _delay_ms(const int ms); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index a98ceb6f391d..2d2a95774c1b 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -92,5 +92,5 @@ 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); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index cee9cfc5f744..541848b08acc 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -31,7 +31,7 @@ DefaultSerial1 USBSerial(false, UsbSerial); -uint32_t HAL_adc_reading = 0; +uint32_t MarlinHAL::adc_result = 0; // U8glib required functions extern "C" { @@ -41,8 +41,6 @@ extern "C" { void u8g_Delay(uint16_t val) { delay(val); } } -//************************// - // return free heap space int freeMemory() { char stack_end; @@ -54,33 +52,33 @@ int freeMemory() { return result; } -// scan command line for code -// return index into pin map array if found and the pin is valid. -// return dval if not found or not a valid pin. -int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { - const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; - const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; - return ind > -1 ? ind : dval; +void MarlinHAL::reboot() { NVIC_SystemReset(); } + +uint8_t MarlinHAL::get_reset_source() { + #if ENABLED(USE_WATCHDOG) + if (watchdog_timed_out()) return RST_WATCHDOG; + #endif + return RST_POWER_ON; +} + +void MarlinHAL::clear_reset_source() { + TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); } void flashFirmware(const int16_t) { delay(500); // Give OS time to disconnect USB_Connect(false); // USB clear connection delay(1000); // Give OS time to notice - HAL_reboot(); + hal.reboot(); } -void HAL_clear_reset_source(void) { - TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); -} - -uint8_t HAL_get_reset_source(void) { - #if ENABLED(USE_WATCHDOG) - if (watchdog_timed_out()) return RST_WATCHDOG; - #endif - return RST_POWER_ON; +// For M42/M43, scan command line for pin code +// return index into pin map array if found and the pin is valid. +// return dval if not found or not a valid pin. +int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { + const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; + const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; + return ind > -1 ? ind : dval; } -void HAL_reboot() { NVIC_SystemReset(); } - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 348ea6b21a04..ba0729590f5b 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -28,8 +28,6 @@ #define CPU_32_BIT -void HAL_init(); - #include #include #include @@ -47,12 +45,9 @@ extern "C" volatile uint32_t _millis; #include #include -// -// Default graphical display delays -// -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 +// ------------------------ +// Serial ports +// ------------------------ typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; @@ -114,26 +109,12 @@ extern DefaultSerial1 USBSerial; // // Interrupts // -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() - -// -// Utility functions -// -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif -int freeMemory(); - -#pragma GCC diagnostic pop +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() // -// ADC API +// ADC // #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift), @@ -152,20 +133,11 @@ int freeMemory(); #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -using FilteredADC = LPC176x::ADC; -extern uint32_t HAL_adc_reading; -[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) { - HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits -} -[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() { - return HAL_adc_reading; -} +#define HAL_ANALOG_SELECT(pin) hal.adc_enable(pin) -#define HAL_adc_init() -#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() (true) +// +// Pin Mapping for M42, M43, M226 +// // Test whether the pin is valid constexpr bool VALID_PIN(const pin_t pin) { @@ -192,32 +164,104 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, -#define HAL_IDLETASK 1 -void HAL_idletask(); +// ------------------------ +// Defines +// ------------------------ #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 - * All Hardware PWM pins run at the same frequency and all - * Software PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, int f_desired); +// Default graphical display delays +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + using FilteredADC = LPC176x::ADC; + + // Called by Temperature::init once at startup + static inline void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const pin_t pin) { + FilteredADC::enable_channel(pin); + } + + // Begin ADC sampling on the given pin + static uint32_t adc_result; + FORCE_INLINE static void adc_start(const pin_t pin) { + adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits + } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + FORCE_INLINE static uint16_t adc_value() { + return (uint16_t)adc_result; + } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); -// Reset source -void HAL_clear_reset_source(void); -uint8_t HAL_get_reset_source(void); + /** + * Set the frequency of the timer corresponding to the provided pin + * All Hardware PWM pins will run at the same frequency and + * All Software PWM pins will run at the same frequency + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); +}; -void HAL_reboot(); +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index eb12fd20f4d8..f02f503a67da 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -65,4 +65,5 @@ class libServo: public Servo { } }; -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index eae0e36b0b0e..91e92a157501 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -21,21 +21,17 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #include -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; if (LPC176x::pwm_attach_pin(pin)) LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } -#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM - - void set_pwm_frequency(const pin_t pin, int f_desired) { - LPC176x::pwm_set_frequency(pin, f_desired); - } - -#endif +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { + LPC176x::pwm_set_frequency(pin, f_desired); +} #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index ef0dc42c78ca..419c99793fb8 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void HAL_init() { +void MarlinHAL::init() { // Init LEDs #if PIN_EXISTS(LED) @@ -130,7 +130,7 @@ void HAL_init() { const millis_t usb_timeout = millis() + 2000; while (!USB_Configuration && PENDING(millis(), usb_timeout)) { delay(50); - HAL_idletask(); + idletask(); #if PIN_EXISTS(LED) TOGGLE(LED_PIN); // Flash quickly during USB initialization #endif @@ -142,7 +142,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 78e856db2857..c6d7bc632e2e 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 436b4b4daa26..bfbdaf211ff3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -21,18 +21,10 @@ */ #pragma once -#define CPU_32_BIT -#define HAL_IDLETASK -void HAL_idletask(); - -#define F_CPU 100000000 -#define SystemCoreClock F_CPU #include #include - #undef min #undef max - #include #include "pinmapping.h" @@ -40,8 +32,6 @@ void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); -//extern "C" volatile uint32_t _millis; - //arduino: Print.h #define DEC 10 #define HEX 16 @@ -58,7 +48,23 @@ uint8_t _getc(); #include "watchdog.h" #include "serial.h" -#define SHARED_SERVOS HAS_SERVOS +// ------------------------ +// Defines +// ------------------------ + +#define CPU_32_BIT +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU + +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// ------------------------ +// Serial ports +// ------------------------ extern MSerialT serial_stream_0; extern MSerialT serial_stream_1; @@ -98,49 +104,20 @@ extern MSerialT serial_stream_3; #endif #endif - -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// +// ------------------------ // Interrupts -// +// ------------------------ + #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() -#define ISRS_ENABLED() -#define ENABLE_ISRS() -#define DISABLE_ISRS() - -inline void HAL_init() {} - -// Utility functions -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -int freeMemory(); -#pragma GCC diagnostic pop +// ------------------------ // ADC +// ------------------------ + #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true - -void HAL_adc_init(); -void HAL_adc_enable_channel(const uint8_t ch); -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); - -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// Reset source -inline void HAL_clear_reset_source(void) {} -inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } - -void HAL_reboot(); +#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) /* ---------------- Delay in cycles */ @@ -159,29 +136,22 @@ constexpr inline std::size_t strlen_constexpr(const char* str) { // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 if (str != nullptr) { std::size_t i = 0; - while (str[i] != '\0') { - ++i; - } - + while (str[i] != '\0') ++i; return i; } - return 0; } constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 - if (lhs == nullptr || rhs == nullptr) { + if (lhs == nullptr || rhs == nullptr) return rhs != nullptr ? -1 : 1; - } - for (std::size_t i = 0; i < count; ++i) { + for (std::size_t i = 0; i < count; ++i) if (lhs[i] != rhs[i]) { return lhs[i] < rhs[i] ? -1 : 1; - } else if (lhs[i] == '\0') { + else if (lhs[i] == '\0') return 0; - } - } return 0; } @@ -193,14 +163,11 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe do { char sc = {}; do { - if ((sc = *str++) == '\0') { - return nullptr; - } + if ((sc = *str++) == '\0') return nullptr; } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } - return str; } @@ -211,12 +178,88 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) { do { char sc = {}; do { - if ((sc = *str++) == '\0') { - return nullptr; - } + if ((sc = *str++) == '\0') return nullptr; } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } return str; } + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return true; } + static inline void isr_on() {} + static inline void isr_off() {} + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static constexpr uint8_t reset_reason = RST_POWER_ON; + static inline uint8_t get_reset_source() { return reset_reason; } + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint8_t active_ch; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const uint8_t ch); + + // Is the ADC ready for reading? + static bool adc_ready(); + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index cedfdb62d631..be38d583b686 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -87,5 +87,5 @@ 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); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 8baad31bc751..f0383251283d 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -106,7 +106,7 @@ // Private Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; #if ADC_IS_REQUIRED @@ -402,7 +402,7 @@ uint16_t HAL_adc_result; // ------------------------ // HAL initialization task -void HAL_init() { +void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) @@ -412,17 +412,9 @@ void HAL_init() { #endif } -// HAL idle task -/* -void HAL_idletask() { -} -*/ - -void HAL_clear_reset_source() { } - #pragma push_macro("WDT") #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { RSTC_RCAUSE_Type resetCause; resetCause.reg = REG_RSTC_RCAUSE; @@ -436,7 +428,7 @@ uint8_t HAL_get_reset_source() { } #pragma pop_macro("WDT") -void HAL_reboot() { NVIC_SystemReset(); } +void MarlinHAL::reboot() { NVIC_SystemReset(); } extern "C" { void * _sbrk(int incr); @@ -454,7 +446,7 @@ int freeMemory() { // ADC // ------------------------ -void HAL_adc_init() { +void MarlinHAL::adc_init() { #if ADC_IS_REQUIRED memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values @@ -491,17 +483,17 @@ void HAL_adc_init() { #endif // ADC_IS_REQUIRED } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t pin) { #if ADC_IS_REQUIRED LOOP_L_N(pi, COUNT(adc_pins)) { - if (adc_pin == adc_pins[pi]) { - HAL_adc_result = HAL_adc_results[pi]; + if (pin == adc_pins[pi]) { + adc_result = HAL_adc_results[pi]; return; } } #endif - HAL_adc_result = 0xFFFF; + adc_result = 0xFFFF; } #endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index c262752a8d66..144bf9c08dfa 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -89,51 +89,31 @@ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp +class Servo; +typedef Servo hal_servo_t; // // Interrupts // -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -#define cli() __disable_irq() // Disable interrupts -#define sei() __enable_irq() // Enable interrupts - -void HAL_clear_reset_source(); // clear reset reason -uint8_t HAL_get_reset_source(); // get reset reason - -void HAL_reboot(); +#define cli() __disable_irq() // Disable interrupts +#define sei() __enable_irq() // Enable interrupts // // ADC // -extern uint16_t HAL_adc_result; // Most recent ADC conversion #define HAL_ANALOG_SELECT(pin) -void HAL_adc_init(); - //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -// -// PWM -// -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } // -// Pin Map +// Pin Mapping for M42, M43, M226 // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -142,35 +122,92 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// Enable hooks into idle and setup for HAL -void HAL_init(); -/* -#define HAL_IDLETASK 1 -void HAL_idletask(); -*/ - -// -// Utility functions -// -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif -int freeMemory(); - -#pragma GCC diagnostic pop - #ifdef __cplusplus extern "C" { #endif + char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); + +extern "C" int freeMemory(); + #ifdef __cplusplus } #endif + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { sei(); } + static inline void isr_off() { cli(); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static inline void idletask() {} + + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 0920a72ec1bc..324a78316a2d 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -53,16 +53,18 @@ // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Public functions // ------------------------ -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); +#if ENABLED(POSTMORTEM_DEBUGGING) + extern void install_min_serial(); +#endif // HAL initialization task -void HAL_init() { +void MarlinHAL::init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. @@ -103,7 +105,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // Stm32duino currently doesn't have a "loop/idle" method CDC_resume_receive(); @@ -111,9 +113,9 @@ void HAL_idletask() { #endif } -void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } +void MarlinHAL::reboot() { NVIC_SystemReset(); } -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { return #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : @@ -137,24 +139,14 @@ uint8_t HAL_get_reset_source() { ; } -void HAL_reboot() { NVIC_SystemReset(); } - -void _delay_ms(const int delay_ms) { delay(delay_ms); } +void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } extern "C" { extern unsigned int _ebss; // end of bss section } -// ------------------------ -// ADC -// ------------------------ - -// TODO: Make sure this doesn't cause any delay -void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - // Reset the system to initiate a firmware flash -WEAK void flashFirmware(const int16_t) { HAL_reboot(); } +WEAK void flashFirmware(const int16_t) { hal.reboot(); } // Maple Compatibility volatile uint32_t systick_uptime_millis = 0; diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index adaf14223f32..d71ccd796b2f 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -44,9 +44,9 @@ #define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_3 340 -// -// Serial Ports -// +// ------------------------ +// Serial ports +// ------------------------ #ifdef USBCON #include #include "../../core/serial_hook.h" @@ -115,17 +115,14 @@ #define analogInputToDigitalPin(p) (p) #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +// +// Interrupts +// +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() #define cli() __disable_irq() #define sei() __enable_irq() -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - // ------------------------ // Types // ------------------------ @@ -136,54 +133,14 @@ typedef int16_t pin_t; #endif -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() // ------------------------ -// Public Variables -// ------------------------ - -// result of last ADC conversion -extern uint16_t HAL_adc_result; - -// ------------------------ -// Public functions -// ------------------------ - -// Memory related -#define __bss_end __bss_end__ - -// Enable hooks into setup for HAL -void HAL_init(); -#define HAL_IDLETASK 1 -void HAL_idletask(); - -// Clear reset reason -void HAL_clear_reset_source(); - -// Reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(const int delay); - -extern "C" char* _sbrk(int incr); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" - -static inline int freeMemory() { - volatile char top; - return &top - reinterpret_cast(_sbrk(0)); -} - -#pragma GCC diagnostic pop - -// // ADC -// +// ------------------------ #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) @@ -194,16 +151,10 @@ static inline int freeMemory() { #endif #define HAL_ADC_VREF 3.3 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -uint16_t HAL_adc_get_result(); +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) @@ -226,17 +177,93 @@ extern volatile uint32_t systick_uptime_millis; #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 - * All Timer PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, int f_desired); +// ------------------------ +// Class Utilities +// ------------------------ -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// Memory related +#define __bss_end __bss_end__ + +extern "C" char* _sbrk(int incr); + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +static inline int freeMemory() { + volatile char top; + return &top - reinterpret_cast(_sbrk(0)); +} + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { sei(); } + static inline void isr_off() { cli(); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static inline void adc_init() { + analogReadResolution(HAL_ADC_RESOLUTION); + } + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 8ee476164785..7737245de85b 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -102,9 +102,9 @@ static SPISettings spiConfig; // Soft SPI receive byte uint8_t spiRec() { - DISABLE_ISRS(); // No interrupts during byte receive + hal.isr_off(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - ENABLE_ISRS(); // Enable interrupts + hal.isr_off(); // Enable interrupts return data; } @@ -116,9 +116,9 @@ static SPISettings spiConfig; // Soft SPI send byte void spiSend(uint8_t data) { - DISABLE_ISRS(); // No interrupts during byte send + hal.isr_off(); // No interrupts during byte send HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts } // Soft SPI send block diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 252b057362c9..7c8cc8dd21e1 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -174,9 +174,9 @@ bool PersistentStore::access_finish() { UNLOCK_FLASH(); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - DISABLE_ISRS(); + hal.isr_off(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); - ENABLE_ISRS(); + hal.isr_on(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); @@ -229,9 +229,9 @@ bool PersistentStore::access_finish() { // output. Servo output still glitches with interrupts disabled, but recovers after the // erase. TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - DISABLE_ISRS(); + hal.isr_off(); eeprom_buffer_flush(); - ENABLE_ISRS(); + hal.isr_on(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index b1bea5ce20eb..f6d0481c05c1 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -29,7 +29,7 @@ // Array to support sticky frequency sets per timer static uint16_t timer_freq[TIMER_NUM]; -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); @@ -56,7 +56,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); } -void set_pwm_frequency(const pin_t pin, int f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index 73d850fc4313..a7f022a0b62d 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -115,7 +115,6 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(ANUM) port_print(ANUM) #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num // x is a variable used to search pin_array #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) @@ -123,6 +122,11 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin +// +// Pin Mapping for M43 +// +#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num + #ifndef M43_NEVER_TOUCH #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) #ifdef KILL_PIN diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index aad543229e16..6828998198af 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index f29b30536146..efc513cf94d2 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -79,7 +79,7 @@ #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ // ------------------------ -// Public Variables +// Serial ports // ------------------------ #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE @@ -112,72 +112,21 @@ #endif #endif -uint16_t HAL_adc_result; - // ------------------------ -// Private Variables +// ADC // ------------------------ -STM32ADC adc(ADC1); -const uint8_t adc_pins[] = { - #if HAS_TEMP_ADC_0 - TEMP_0_PIN, - #endif - #if HAS_TEMP_ADC_PROBE - TEMP_PROBE_PIN, - #endif - #if HAS_HEATED_BED - TEMP_BED_PIN, - #endif - #if HAS_TEMP_CHAMBER - TEMP_CHAMBER_PIN, - #endif - #if HAS_TEMP_COOLER - TEMP_COOLER_PIN, - #endif - #if HAS_TEMP_ADC_1 - TEMP_1_PIN, - #endif - #if HAS_TEMP_ADC_2 - TEMP_2_PIN, - #endif - #if HAS_TEMP_ADC_3 - TEMP_3_PIN, - #endif - #if HAS_TEMP_ADC_4 - TEMP_4_PIN, - #endif - #if HAS_TEMP_ADC_5 - TEMP_5_PIN, - #endif - #if HAS_TEMP_ADC_6 - TEMP_6_PIN, - #endif - #if HAS_TEMP_ADC_7 - TEMP_7_PIN, - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - FILWIDTH_PIN, - #endif - #if HAS_ADC_BUTTONS - ADC_KEYPAD_PIN, - #endif - #if HAS_JOY_ADC_X - JOY_X_PIN, - #endif - #if HAS_JOY_ADC_Y - JOY_Y_PIN, - #endif - #if HAS_JOY_ADC_Z - JOY_Z_PIN, - #endif - #if ENABLED(POWER_MONITOR_CURRENT) - POWER_MONITOR_CURRENT_PIN, - #endif - #if ENABLED(POWER_MONITOR_VOLTAGE) - POWER_MONITOR_VOLTAGE_PIN, - #endif -}; +uint16_t analogRead(pin_t pin) { + const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; + return is_analog ? analogRead(uint8_t(pin)) : 0; +} + +// Wrapper to maple unprotected analogWrite +void analogWrite(pin_t pin, int pwm_val8) { + if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); +} + +uint16_t MarlinHAL::adc_result; enum TempPinIndex : char { #if HAS_TEMP_ADC_0 @@ -245,15 +194,16 @@ uint16_t HAL_adc_results[ADC_PIN_COUNT]; // ------------------------ // Private functions // ------------------------ + static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = SCB->AIRCR; // read old register configuration + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key & priority group */ + (PriorityGroupTmp << 8)); // Insert write key & priority group SCB->AIRCR = reg_value; } @@ -261,6 +211,8 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { // Public functions // ------------------------ +void flashFirmware(const int16_t) { hal.reboot(); } + // // Leave PA11/PA12 intact if USBSerial is not used // @@ -280,7 +232,11 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void HAL_init() { +// ------------------------ +// MarlinHAL class +// ------------------------ + +void MarlinHAL::init() { NVIC_SetPriorityGrouping(0x3); #if PIN_EXISTS(LED) OUT_WRITE(LED_PIN, LOW); @@ -299,7 +255,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. @@ -314,14 +270,7 @@ void HAL_idletask() { #endif } -void HAL_clear_reset_source() { } - -/** - * TODO: Check this and change or remove. - */ -uint8_t HAL_get_reset_source() { return RST_POWER_ON; } - -void _delay_ms(const int delay_ms) { delay(delay_ms); } +void MarlinHAL::reboot() { nvic_sys_reset(); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -355,11 +304,70 @@ extern "C" { } */ -// ------------------------ // ADC -// ------------------------ + // Init the AD in continuous capture mode -void HAL_adc_init() { +void MarlinHAL::adc_init() { + static const uint8_t adc_pins[] = { + #if HAS_TEMP_ADC_0 + TEMP_0_PIN, + #endif + #if HAS_TEMP_ADC_PROBE + TEMP_PROBE_PIN, + #endif + #if HAS_HEATED_BED + TEMP_BED_PIN, + #endif + #if HAS_TEMP_CHAMBER + TEMP_CHAMBER_PIN, + #endif + #if HAS_TEMP_COOLER + TEMP_COOLER_PIN, + #endif + #if HAS_TEMP_ADC_1 + TEMP_1_PIN, + #endif + #if HAS_TEMP_ADC_2 + TEMP_2_PIN, + #endif + #if HAS_TEMP_ADC_3 + TEMP_3_PIN, + #endif + #if HAS_TEMP_ADC_4 + TEMP_4_PIN, + #endif + #if HAS_TEMP_ADC_5 + TEMP_5_PIN, + #endif + #if HAS_TEMP_ADC_6 + TEMP_6_PIN, + #endif + #if HAS_TEMP_ADC_7 + TEMP_7_PIN, + #endif + #if ENABLED(FILAMENT_WIDTH_SENSOR) + FILWIDTH_PIN, + #endif + #if HAS_ADC_BUTTONS + ADC_KEYPAD_PIN, + #endif + #if HAS_JOY_ADC_X + JOY_X_PIN, + #endif + #if HAS_JOY_ADC_Y + JOY_Y_PIN, + #endif + #if HAS_JOY_ADC_Z + JOY_Z_PIN, + #endif + #if ENABLED(POWER_MONITOR_CURRENT) + POWER_MONITOR_CURRENT_PIN, + #endif + #if ENABLED(POWER_MONITOR_VOLTAGE) + POWER_MONITOR_VOLTAGE_PIN, + #endif + }; + static STM32ADC adc(ADC1); // configure the ADC adc.calibrate(); #if F_CPU > 72000000 @@ -374,10 +382,10 @@ void HAL_adc_init() { adc.startConversion(); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t pin) { //TEMP_PINS pin_index; TempPinIndex pin_index; - switch (adc_pin) { + switch (pin) { default: return; #if HAS_TEMP_ADC_0 case TEMP_0_PIN: pin_index = TEMP_0; break; @@ -440,20 +448,4 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - -uint16_t analogRead(pin_t pin) { - const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; - return is_analog ? analogRead(uint8_t(pin)) : 0; -} - -// Wrapper to maple unprotected analogWrite -void analogWrite(pin_t pin, int pwm_val8) { - if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); -} - -void HAL_reboot() { nvic_sys_reset(); } - -void flashFirmware(const int16_t) { HAL_reboot(); } - #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 153cfe8ac89e..517c8f2cb808 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -66,6 +66,10 @@ #endif #endif +// ------------------------ +// Serial ports +// ------------------------ + #ifdef SERIAL_USB typedef ForwardSerial1Class< USBSerial > DefaultSerial1; extern DefaultSerial1 MSerial0; @@ -141,11 +145,6 @@ #endif #endif -// Set interrupt grouping for this MCU -void HAL_init(); -#define HAL_IDLETASK 1 -void HAL_idletask(); - /** * TODO: review this to return 1 for pins that are not analog input */ @@ -158,15 +157,7 @@ void HAL_idletask(); #define NO_COMPILE_TIME_PWM #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() -#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() ((void)__iSeiRetVal()) -#define DISABLE_ISRS() ((void)__iCliRetVal()) - -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - +// Reset Reason #define RST_POWER_ON 1 #define RST_EXTERNAL 2 #define RST_BROWN_OUT 4 @@ -181,62 +172,24 @@ void HAL_idletask(); typedef int8_t pin_t; -// ------------------------ -// Public Variables -// ------------------------ - // Result of last ADC conversion extern uint16_t HAL_adc_result; // ------------------------ -// Public functions +// Interrupts // ------------------------ -// Disable interrupts +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); (void)__iCliRetVal() +#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() #define cli() noInterrupts() - -// Enable interrupts #define sei() interrupts() -// Memory related -#define __bss_end __bss_end__ - -// Clear reset reason -void HAL_clear_reset_source(); - -// Reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(const int delay); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" - -/* -extern "C" { - int freeMemory(); -} -*/ - -extern "C" char* _sbrk(int incr); - -static inline int freeMemory() { - volatile char top; - return &top - _sbrk(0); -} - -#pragma GCC diagnostic pop - -// +// ------------------------ // ADC -// +// ------------------------ #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); -void HAL_adc_init(); - #ifdef ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION #else @@ -244,43 +197,116 @@ void HAL_adc_init(); #endif #define HAL_ADC_VREF 3.3 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) +#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment #ifndef PWM_FREQUENCY #define PWM_FREQUENCY 1000 // Default PWM Frequency #endif -#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 - * All Timer PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, int f_desired); +// ------------------------ +// Class Utilities +// ------------------------ -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// Memory related +#define __bss_end __bss_end__ + +void _delay_ms(const int ms); + +extern "C" char* _sbrk(int incr); + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +static inline int freeMemory() { + volatile char top; + return &top - _sbrk(0); +} + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_primask(); } + static inline void isr_on() { ((void)__iSeiRetVal()); } + static inline void isr_off() { ((void)__iCliRetVal()); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static inline uint8_t get_reset_source() { return RST_POWER_ON; } + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index b6143de81d62..745a1c93f07d 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -35,7 +35,8 @@ #define SERVO_DEFAULT_MIN_ANGLE 0 #define SERVO_DEFAULT_MAX_ANGLE 180 -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; class libServo { public: diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 98d56bc5e931..11a1a107123e 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -21,11 +21,9 @@ */ #ifdef __STM32F1__ -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #include -#include "HAL.h" -#include "timers.h" #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) @@ -38,7 +36,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { return 0; } -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; timer_dev *timer; UNUSED(timer); @@ -51,7 +49,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode } -void set_pwm_frequency(const pin_t pin, int f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer timer_dev *timer; UNUSED(timer); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index f9ab6d13d374..0cd807fc8479 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index f08cf799e9e8..b923ab77b1f1 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -31,6 +31,10 @@ #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -40,33 +44,32 @@ #endif USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result; - -static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) - 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 - 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) - 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. -}; - -/* - // disable interrupts - void cli() { noInterrupts(); } +// ------------------------ +// Class Utilities +// ------------------------ - // enable interrupts - void sei() { interrupts(); } -*/ +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void HAL_adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void HAL_clear_reset_source() { } +// ------------------------ +// MarlinHAL Class +// ------------------------ -uint8_t HAL_get_reset_source() { +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -78,25 +81,25 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; } +void MarlinHAL::adc_start(const pin_t pin) { + static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) + 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 + 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) + 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. + }; + ADC0_SC1A = pin2sc1a[pin]; +} -uint16_t HAL_adc_get_result() { return ADC0_RA; } +uint16_t MarlinHAL::adc_value() { return ADC0_RA; } #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 61d8b34604c5..fdf914b1b02e 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,12 +36,9 @@ #include -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -//#undef MOTHERBOARD -//#define MOTHERBOARD BOARD_TEENSY31_32 +// ------------------------ +// Defines +// ------------------------ #define IS_32BIT_TEENSY 1 #define IS_TEENSY_31_32 1 @@ -49,6 +46,14 @@ #define IS_TEENSY32 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" #define Serial0 Serial @@ -72,31 +77,46 @@ extern USBSerialType USBSerial; #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; +// ------------------------ +// Interrupts +// ------------------------ + +uint32_t __get_PRIMASK(void); // CMSIS +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() + +// ------------------------ +// ADC +// ------------------------ + #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() - -inline void HAL_init() {} - -// Clear the reset reason -void HAL_clear_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 -// Get the reason for the reset -uint8_t HAL_get_reset_source(); +#define HAL_ANALOG_SELECT(pin) -void HAL_reboot(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -107,27 +127,64 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } -// PWM + static inline void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static inline void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t ch); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 3b073d63ab29..9fcbb6f232c9 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 046c00b56ed5..54a5ad385536 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -31,6 +31,10 @@ #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -39,42 +43,34 @@ USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result, HAL_adc_select; - -static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 - 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only - 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 - 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only - 10+128, 11+128, // 49-50 are A23-A24 - 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only - 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only - 3, 19+128, // 64-65 are A10-A11 - 23, 23+128,// 66-67 are A21-A22 (DAC pins) - 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) - 26, // 70 is Temperature Sensor - 18+128 // 71 is Vref -}; - -/* - // disable interrupts - void cli() { noInterrupts(); } - - // enable interrupts - void sei() { interrupts(); } -*/ - -void HAL_adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); +// ------------------------ +// Class Utilities +// ------------------------ + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void HAL_clear_reset_source() { } +// ------------------------ +// MarlinHAL Class +// ------------------------ -uint8_t HAL_get_reset_source() { +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +// Reset + +uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -86,41 +82,49 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +int8_t MarlinHAL::adc_select; - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } + while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } + NVIC_ENABLE_IRQ(IRQ_FTM1); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t adc_pin) { + static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 + 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only + 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 + 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only + 10+128, 11+128, // 49-50 are A23-A24 + 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only + 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only + 3, 19+128, // 64-65 are A10-A11 + 23, 23+128,// 66-67 are A21-A22 (DAC pins) + 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) + 26, // 70 is Temperature Sensor + 18+128 // 71 is Vref + }; const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - // Digital only - HAL_adc_select = -1; + adc_select = -1; // Digital only } else if (pin & 0x80) { - HAL_adc_select = 1; + adc_select = 1; ADC1_SC1A = pin & 0x7F; } else { - HAL_adc_select = 0; + adc_select = 0; ADC0_SC1A = pin; } } -uint16_t HAL_adc_get_result() { - switch (HAL_adc_select) { +uint16_t MarlinHAL::adc_value() { + switch (adc_select) { case 0: return ADC0_RA; case 1: return ADC1_RA; } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 892eb2d3c5b8..5506599cdf03 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,10 +37,6 @@ #include #include -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // ------------------------ // Defines // ------------------------ @@ -53,6 +49,17 @@ #define IS_TEENSY35 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +#undef sq +#define sq(x) ((x)*(x)) + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" #define Serial0 Serial @@ -76,34 +83,45 @@ extern USBSerialType USBSerial; #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +// ------------------------ +// Interrupts +// ------------------------ -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -#undef sq -#define sq(x) ((x)*(x)) +// ------------------------ +// ADC +// ------------------------ -inline void HAL_init() {} +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Clear reset reason -void HAL_clear_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 -// Reset reason -uint8_t HAL_get_reset_source(); +#define HAL_ANALOG_SELECT(pin) -void HAL_reboot(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -114,27 +132,66 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static inline bool isr_state() { return true; } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } -// PWM + static inline void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static inline void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static int8_t adc_select; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const pin_t) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 6c342bbe0d25..8af79d73928e 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 270bee0dc9d4..68bd38f72ff8 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -33,6 +33,10 @@ #include "timers.h" #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -40,75 +44,42 @@ #endif USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result, HAL_adc_select; - -static const uint8_t pin2sc1a[] = { - 0x07, // 0/A0 AD_B1_02 - 0x08, // 1/A1 AD_B1_03 - 0x0C, // 2/A2 AD_B1_07 - 0x0B, // 3/A3 AD_B1_06 - 0x06, // 4/A4 AD_B1_01 - 0x05, // 5/A5 AD_B1_00 - 0x0F, // 6/A6 AD_B1_10 - 0x00, // 7/A7 AD_B1_11 - 0x0D, // 8/A8 AD_B1_08 - 0x0E, // 9/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - 0x07, // 14/A0 AD_B1_02 - 0x08, // 15/A1 AD_B1_03 - 0x0C, // 16/A2 AD_B1_07 - 0x0B, // 17/A3 AD_B1_06 - 0x06, // 18/A4 AD_B1_01 - 0x05, // 19/A5 AD_B1_00 - 0x0F, // 20/A6 AD_B1_10 - 0x00, // 21/A7 AD_B1_11 - 0x0D, // 22/A8 AD_B1_08 - 0x0E, // 23/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - #ifdef ARDUINO_TEENSY41 - 0xFF, // 28 - 0xFF, // 29 - 0xFF, // 30 - 0xFF, // 31 - 0xFF, // 32 - 0xFF, // 33 - 0xFF, // 34 - 0xFF, // 35 - 0xFF, // 36 - 0xFF, // 37 - 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 - 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 - 0x09, // 40/A16 AD_B1_04 - 0x0A, // 41/A17 AD_B1_05 - #endif -}; - -/* -// disable interrupts -void cli() { noInterrupts(); } - -// enable interrupts -void sei() { interrupts(); } -*/ - -void HAL_adc_init() { - analog_init(); - while (ADC1_GC & ADC_GC_CAL) ; - while (ADC2_GC & ADC_GC_CAL) ; +// ------------------------ +// Class Utilities +// ------------------------ + +#define __bss_end _ebss + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + // Doesn't work on Teensy 4.x + uint32_t freeMemory() { + uint32_t free_memory; + free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); + return free_memory; + } } -void HAL_clear_reset_source() { - uint32_t reset_source = SRC_SRSR; - SRC_SRSR = reset_source; +// ------------------------ +// FastIO +// ------------------------ + +bool is_output(pin_t pin) { + const struct digital_pin_bitband_and_config_table_struct *p; + p = digital_pin_to_info_PGM + pin; + return (*(p->reg + 1) & p->mask); } -uint8_t HAL_get_reset_source() { +// ------------------------ +// MarlinHAL Class +// ------------------------ + +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +uint8_t MarlinHAL::get_reset_source() { switch (SRC_SRSR & 0xFF) { case 1: return RST_POWER_ON; break; case 2: return RST_SOFTWARE; break; @@ -121,57 +92,92 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +void MarlinHAL::clear_reset_source() { + uint32_t reset_source = SRC_SRSR; + SRC_SRSR = reset_source; +} -#define __bss_end _ebss +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +int8_t MarlinHAL::adc_select; - // Doesn't work on Teensy 4.x - uint32_t freeMemory() { - uint32_t free_memory; - if ((uint32_t)__brkval == 0) - free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end); - else - free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC1_GC & ADC_GC_CAL) { /* wait */ } + while (ADC2_GC & ADC_GC_CAL) { /* wait */ } } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t adc_pin) { + static const uint8_t pin2sc1a[] = { + 0x07, // 0/A0 AD_B1_02 + 0x08, // 1/A1 AD_B1_03 + 0x0C, // 2/A2 AD_B1_07 + 0x0B, // 3/A3 AD_B1_06 + 0x06, // 4/A4 AD_B1_01 + 0x05, // 5/A5 AD_B1_00 + 0x0F, // 6/A6 AD_B1_10 + 0x00, // 7/A7 AD_B1_11 + 0x0D, // 8/A8 AD_B1_08 + 0x0E, // 9/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + 0x07, // 14/A0 AD_B1_02 + 0x08, // 15/A1 AD_B1_03 + 0x0C, // 16/A2 AD_B1_07 + 0x0B, // 17/A3 AD_B1_06 + 0x06, // 18/A4 AD_B1_01 + 0x05, // 19/A5 AD_B1_00 + 0x0F, // 20/A6 AD_B1_10 + 0x00, // 21/A7 AD_B1_11 + 0x0D, // 22/A8 AD_B1_08 + 0x0E, // 23/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + #ifdef ARDUINO_TEENSY41 + 0xFF, // 28 + 0xFF, // 29 + 0xFF, // 30 + 0xFF, // 31 + 0xFF, // 32 + 0xFF, // 33 + 0xFF, // 34 + 0xFF, // 35 + 0xFF, // 36 + 0xFF, // 37 + 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 + 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 + 0x09, // 40/A16 AD_B1_04 + 0x0A, // 41/A17 AD_B1_05 + #endif + }; const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - HAL_adc_select = -1; // Digital only + adc_select = -1; // Digital only } else if (pin & 0x80) { - HAL_adc_select = 1; + adc_select = 1; ADC2_HC0 = pin & 0x7F; } else { - HAL_adc_select = 0; + adc_select = 0; ADC1_HC0 = pin; } } -uint16_t HAL_adc_get_result() { - switch (HAL_adc_select) { +uint16_t MarlinHAL::adc_value() { + switch (adc_select) { case 0: - while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait + while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ } return ADC1_R0; case 1: - while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait + while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ } return ADC2_R0; } return 0; } -bool is_output(pin_t pin) { - const struct digital_pin_bitband_and_config_table_struct *p; - p = digital_pin_to_info_PGM + pin; - return (*(p->reg + 1) & p->mask); -} - #endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 2b730768a802..4a0b5688d77c 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,10 +41,6 @@ #include "../../feature/ethernet.h" #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // ------------------------ // Defines // ------------------------ @@ -55,7 +51,23 @@ #define IS_TEENSY41 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +#undef sq +#define sq(x) ((x)*(x)) + +// Don't place string constants in PROGMEM +#undef PSTR +#define PSTR(str) ({static const char *data = (str); &data[0];}) + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" + #define Serial0 Serial #define _DECLARE_SERIAL(X) \ typedef ForwardSerial1Class DefaultSerial##X; \ @@ -89,41 +101,49 @@ extern USBSerialType USBSerial; #endif #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +// ------------------------ +// Interrupts +// ------------------------ -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -#undef sq -#define sq(x) ((x)*(x)) +// ------------------------ +// ADC +// ------------------------ -// Don't place string constants in PROGMEM -#undef PSTR -#define PSTR(str) ({static const char *data = (str); &data[0];}) +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -FORCE_INLINE void HAL_idletask() {} -FORCE_INLINE void HAL_init() {} +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_FILTERED // turn off ADC oversampling -// Clear reset reason -void HAL_clear_reset_source(); +#define HAL_ANALOG_SELECT(pin) -// Reset reason -uint8_t HAL_get_reset_source(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -void HAL_reboot(); +// FastIO +bool is_output(pin_t pin); -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -134,30 +154,66 @@ extern "C" uint32_t freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ADC_FILTERED // turn off ADC oversampling -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static inline bool isr_state() { return !__get_primask(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } -// PWM + static inline void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static inline void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static inline int freeMemory() { return freeMemory(); } -bool is_output(pin_t pin); + // + // ADC Methods + // + + static int8_t adc_select; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 81cf67f7bc08..77fe0953d3bd 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); //void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/shared/HAL.cpp b/Marlin/src/HAL/shared/HAL.cpp new file mode 100644 index 000000000000..a5fe407188db --- /dev/null +++ b/Marlin/src/HAL/shared/HAL.cpp @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * HAL/shared/HAL.cpp + */ + +#include "../../inc/MarlinConfig.h" + +MarlinHAL hal; + +#if ENABLED(SOFT_RESET_VIA_SERIAL) + + // Global for use by e_parser.h + void HAL_reboot() { hal.reboot(); } + +#endif diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp index bd85dbe7bd7e..5d4ce89b2748 100644 --- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp +++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp @@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) { // First device in chain has data sent last extDigitalWrite(ss_pin, LOW); - DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t data_out = L6470_SpiTransfer_Mode_3(data); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts extDigitalWrite(ss_pin, HIGH); return data_out; @@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain extDigitalWrite(ss_pin, LOW); for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted - DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP)); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts if (i == chain_position) data_out = temp; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5132d07e8711..009edeba2f58 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) { #endif // Run HAL idle tasks - TERN_(HAL_IDLETASK, HAL_idletask()); + hal.idletask(); // Check network connection TERN_(HAS_ETHERNET, ethernet.check()); @@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) { watchdog_refresh(); // Reboot the board - HAL_reboot(); + hal.reboot(); #else @@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() { * • L64XX Stepper Drivers (SPI) * • Stepper Driver Reset: DISABLE * • TMC Stepper Drivers (SPI) - * • Run BOARD_INIT if defined + * • Run hal.init_board() for additional pins setup * • ESP WiFi * - Get the Reset Reason and report it * - Print startup messages and diagnostics @@ -1119,8 +1119,8 @@ void setup() { tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable // Check startup - does nothing if bootloader sets MCUSR to 0 - const byte mcu = HAL_get_reset_source(); - HAL_clear_reset_source(); + const byte mcu = hal.get_reset_source(); + hal.clear_reset_source(); #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { @@ -1181,23 +1181,20 @@ void setup() { JTAGSWD_RESET(); #endif - #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) + // Disable any hardware debug to free up pins for IO + #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) delay(10); - // Disable any hardware debug to free up pins for IO - #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) - SETUP_LOG("JTAGSWD_DISABLE"); - JTAGSWD_DISABLE(); - #elif defined(JTAG_DISABLE) - SETUP_LOG("JTAG_DISABLE"); - JTAG_DISABLE(); - #else - #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." - #endif + SETUP_LOG("JTAGSWD_DISABLE"); + JTAGSWD_DISABLE(); + #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE) + delay(10); + SETUP_LOG("JTAG_DISABLE"); + JTAG_DISABLE(); #endif TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime - SETUP_RUN(HAL_init()); + SETUP_RUN(hal.init()); // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) @@ -1243,19 +1240,16 @@ void setup() { SETUP_RUN(tmc_init_cs_pins()); #endif - #ifdef BOARD_INIT - SETUP_LOG("BOARD_INIT"); - BOARD_INIT(); - #endif + SETUP_RUN(hal.init_board()); SETUP_RUN(esp_wifi_init()); // Report Reset Reason - if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); - if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); + if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); + if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); - if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); - if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); + if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); + if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); @@ -1266,7 +1260,7 @@ void setup() { ); #endif SERIAL_ECHO_MSG(" Compiled: " __DATE__); - SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Some HAL need precise delay adjustment calibrate_delay_loop(); @@ -1538,7 +1532,7 @@ void setup() { #endif #if ENABLED(USE_WATCHDOG) - SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call + SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 59832fd6edd7..a58cb66affc7 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -69,7 +69,7 @@ void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS if (pin_is_pwm()) - set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( + hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct #else diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 59ba665e1114..f42bf52ae40a 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -76,7 +76,7 @@ void ControllerFan::update() { thermalManager.soft_pwm_controller_speed = speed; #else if (PWM_PIN(CONTROLLER_FAN_PIN)) - set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); else WRITE(CONTROLLER_FAN_PIN, speed > 0); #endif diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 1dee0cf7550c..fda1ba144bc4 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -41,7 +41,9 @@ extern bool wait_for_user, wait_for_heatup; void quickresume_stepper(); #endif -void HAL_reboot(); +#if ENABLED(SOFT_RESET_VIA_SERIAL) + void HAL_reboot(); +#endif class EmergencyParser { diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 17d790b8cc9a..0a4b5114769d 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -123,7 +123,7 @@ void LEDLights::set_color(const LEDColor &incol // If the pins can do PWM then their intensity will be set. #define _UPDATE_RGBW(C,c) do { \ if (PWM_PIN(RGB_LED_##C##_PIN)) \ - set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ + hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ else \ WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index cde2b47d90aa..2840a92c5838 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -66,10 +66,10 @@ void SpindleLaser::init() { #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed + hal.set_pwm_duty(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); + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif #if ENABLED(AIR_EVACUATION) @@ -90,10 +90,10 @@ void SpindleLaser::init() { * @param ocr Power value */ void SpindleLaser::_set_ocr(const uint8_t ocr) { - #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY - set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); + #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); #endif - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } void SpindleLaser::set_ocr(const uint8_t ocr) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 95d60ae48674..0415c9c8bb1c 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -103,7 +103,7 @@ class SpindleLaser { static void init(); #if ENABLED(MARLIN_DEV_MODE) - static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 77c0ccc49b0f..807681831723 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -126,10 +126,10 @@ void GcodeSuite::M42() { extDigitalWrite(pin, pin_status); #ifdef ARDUINO_ARCH_STM32 - // A simple I/O will be set to 0 by set_pwm_duty() + // A simple I/O will be set to 0 by hal.set_pwm_duty() if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif - set_pwm_duty(pin, pin_status); + hal.set_pwm_duty(pin, pin_status); } #endif // DIRECT_PIN_CONTROL diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 204455e65ec6..2dd1de00013b 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -38,7 +38,7 @@ #include "../sd/cardreader.h" #include "../MarlinCore.h" // for kill -extern void dump_delay_accuracy_check(); +void dump_delay_accuracy_check(); /** * Dn: G-code for development and testing @@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) { for (;;) { /* loop forever (watchdog reset) */ } case 0: - HAL_reboot(); + hal.reboot(); break; case 10: @@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) { settings.reset(); settings.save(); #endif - HAL_reboot(); + hal.reboot(); } break; case 2: { // D2 Read / Write SRAM @@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) { SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); thermalManager.disable_all_heaters(); delay(1000); // Allow time to print - DISABLE_ISRS(); + hal.isr_off(); // Use a low-level delay that does not rely on interrupts to function // Do not spin forever, to avoid thermal risks if heaters are enabled and // watchdog does not work. for (int i = 10000; i--;) DELAY_US(1000UL); - ENABLE_ISRS(); + hal.isr_on(); SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); } break; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c8ac48f7cff5..6ee58f769bde 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3850,3 +3850,10 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _TEST_PWM #undef _LINEAR_AXES_STR #undef _LOGICAL_AXES_STR + +// JTAG support in the HAL +#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE) + #error "DISABLE_DEBUG is not supported for the selected MCU/Board." +#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE) + #error "DISABLE_JTAG is not supported for the selected MCU/Board." +#endif diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 59c74148adef..61db2db9209b 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -282,9 +282,9 @@ void MarlinUI::init_lcd() { #if PIN_EXISTS(LCD_RESET) // Perform a clean hardware reset with needed delays OUT_WRITE(LCD_RESET_PIN, LOW); - _delay_ms(5); + hal.delay_ms(5); WRITE(LCD_RESET_PIN, HIGH); - _delay_ms(5); + hal.delay_ms(5); u8g.begin(); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index d1a9ba7077fd..64a65bb6863b 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -2149,7 +2149,7 @@ void RebootPrinter() { thermalManager.disable_all_heaters(); planner.finish_and_disable(); DWIN_RebootScreen(); - HAL_reboot(); + hal.reboot(); } void Goto_InfoMenu(){ diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7a2cefdd4cea..df6a85780350 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1345,7 +1345,7 @@ void Endstops::update() { ES_REPORT_CHANGE(K_MAX); #endif SERIAL_ECHOLNPGM("\n"); - set_pwm_duty(pin_t(LED_PIN), local_LED_status); + hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; old_live_state_local = live_state_local; } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 45ccdd1702ef..752834c6ab99 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1264,7 +1264,7 @@ void Planner::recalculate() { #if ENABLED(FAN_SOFT_PWM) #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); #else - #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) @@ -1400,8 +1400,8 @@ void Planner::check_axes_activity() { TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) - TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); - TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); + TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 231efe84e1f2..96d5ba9da837 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -30,7 +30,7 @@ #include "servo.h" -HAL_SERVO_LIB servo[NUM_SERVOS]; +hal_servo_t servo[NUM_SERVOS]; #if ENABLED(EDITABLE_SERVO_ANGLES) uint16_t servo_angles[NUM_SERVOS][2]; diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index 73dbbdddb729..cd55a317a275 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -112,5 +112,5 @@ #define MOVE_SERVO(I, P) servo[I].move(P) #define DETACH_SERVO(I) servo[I].detach() -extern HAL_SERVO_LIB servo[NUM_SERVOS]; +extern hal_servo_t servo[NUM_SERVOS]; void servo_init(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index c100051f9808..0f47d66791c4 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1474,7 +1474,7 @@ void Stepper::isr() { #ifndef __AVR__ // Disable interrupts, to avoid ISR preemption while we reprogram the period // (AVR enters the ISR with global interrupts disabled, so no need to do it here) - DISABLE_ISRS(); + hal.isr_off(); #endif // Program timer compare for the maximum period, so it does NOT @@ -1492,7 +1492,7 @@ void Stepper::isr() { hal_timer_t min_ticks; do { // Enable ISRs to reduce USART processing latency - ENABLE_ISRS(); + hal.isr_on(); if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses @@ -1576,7 +1576,7 @@ void Stepper::isr() { * is less than the current count due to something preempting between the * read and the write of the new period value). */ - DISABLE_ISRS(); + hal.isr_off(); /** * Get the current tick value + margin @@ -1611,7 +1611,7 @@ void Stepper::isr() { HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); // Don't forget to finally reenable interrupts - ENABLE_ISRS(); + hal.isr_on(); } #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE @@ -3261,7 +3261,7 @@ void Stepper::report_positions() { #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { case 0: #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index dccdc55034fd..1960dc5d9b52 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -326,7 +326,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) #endif #if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) + #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY) #else #define SET_FAST_PWM_FREQ(P) NOOP #endif @@ -813,7 +813,7 @@ volatile bool Temperature::raw_temps_ready = false; } // Run HAL idle tasks - TERN_(HAL_IDLETASK, HAL_idletask()); + hal.idletask(); // Run UI update TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); @@ -912,7 +912,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _UPDATE_AUTO_FAN(P,D,A) do{ \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ - set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ + hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ else \ WRITE(P##_AUTO_FAN_PIN, D); \ }while(0) @@ -2326,73 +2326,73 @@ void Temperature::init() { TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); - HAL_adc_init(); + hal.adc_init(); #if HAS_TEMP_ADC_0 - HAL_ANALOG_SELECT(TEMP_0_PIN); + hal.adc_enable(TEMP_0_PIN); #endif #if HAS_TEMP_ADC_1 - HAL_ANALOG_SELECT(TEMP_1_PIN); + hal.adc_enable(TEMP_1_PIN); #endif #if HAS_TEMP_ADC_2 - HAL_ANALOG_SELECT(TEMP_2_PIN); + hal.adc_enable(TEMP_2_PIN); #endif #if HAS_TEMP_ADC_3 - HAL_ANALOG_SELECT(TEMP_3_PIN); + hal.adc_enable(TEMP_3_PIN); #endif #if HAS_TEMP_ADC_4 - HAL_ANALOG_SELECT(TEMP_4_PIN); + hal.adc_enable(TEMP_4_PIN); #endif #if HAS_TEMP_ADC_5 - HAL_ANALOG_SELECT(TEMP_5_PIN); + hal.adc_enable(TEMP_5_PIN); #endif #if HAS_TEMP_ADC_6 - HAL_ANALOG_SELECT(TEMP_6_PIN); + hal.adc_enable(TEMP_6_PIN); #endif #if HAS_TEMP_ADC_7 - HAL_ANALOG_SELECT(TEMP_7_PIN); + hal.adc_enable(TEMP_7_PIN); #endif #if HAS_JOY_ADC_X - HAL_ANALOG_SELECT(JOY_X_PIN); + hal.adc_enable(JOY_X_PIN); #endif #if HAS_JOY_ADC_Y - HAL_ANALOG_SELECT(JOY_Y_PIN); + hal.adc_enable(JOY_Y_PIN); #endif #if HAS_JOY_ADC_Z - HAL_ANALOG_SELECT(JOY_Z_PIN); + hal.adc_enable(JOY_Z_PIN); #endif #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif #if HAS_TEMP_ADC_BED - HAL_ANALOG_SELECT(TEMP_BED_PIN); + hal.adc_enable(TEMP_BED_PIN); #endif #if HAS_TEMP_ADC_CHAMBER - HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); + hal.adc_enable(TEMP_CHAMBER_PIN); #endif #if HAS_TEMP_ADC_COOLER - HAL_ANALOG_SELECT(TEMP_COOLER_PIN); + hal.adc_enable(TEMP_COOLER_PIN); #endif #if HAS_TEMP_ADC_PROBE - HAL_ANALOG_SELECT(TEMP_PROBE_PIN); + hal.adc_enable(TEMP_PROBE_PIN); #endif #if HAS_TEMP_ADC_BOARD - HAL_ANALOG_SELECT(TEMP_BOARD_PIN); + hal.adc_enable(TEMP_BOARD_PIN); #endif #if HAS_TEMP_ADC_REDUNDANT - HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); + hal.adc_enable(TEMP_REDUNDANT_PIN); #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - HAL_ANALOG_SELECT(FILWIDTH_PIN); + hal.adc_enable(FILWIDTH_PIN); #endif #if HAS_ADC_BUTTONS - HAL_ANALOG_SELECT(ADC_KEYPAD_PIN); + hal.adc_enable(ADC_KEYPAD_PIN); #endif #if ENABLED(POWER_MONITOR_CURRENT) - HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN); + hal.adc_enable(POWER_MONITOR_CURRENT_PIN); #endif #if ENABLED(POWER_MONITOR_VOLTAGE) - HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); + hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN); #endif HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); @@ -3333,8 +3333,8 @@ void Temperature::isr() { * This gives each ADC 0.9765ms to charge up. */ #define ACCUMULATE_ADC(obj) do{ \ - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \ - else obj.sample(HAL_READ_ADC()); \ + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \ + else obj.sample(hal.adc_value()); \ }while(0) ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling; @@ -3366,115 +3366,115 @@ void Temperature::isr() { break; #if HAS_TEMP_ADC_0 - case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break; + case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break; case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif #if HAS_TEMP_ADC_BED - case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; + case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif #if HAS_TEMP_ADC_CHAMBER - case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; + case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif #if HAS_TEMP_ADC_COOLER - case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; + case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break; case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; #endif #if HAS_TEMP_ADC_PROBE - case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; + case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif #if HAS_TEMP_ADC_BOARD - case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; + case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break; case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; #endif #if HAS_TEMP_ADC_REDUNDANT - case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; + case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; #endif #if HAS_TEMP_ADC_1 - case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; + case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 - case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break; + case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break; case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break; #endif #if HAS_TEMP_ADC_3 - case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break; + case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break; case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break; #endif #if HAS_TEMP_ADC_4 - case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break; + case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break; case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break; #endif #if HAS_TEMP_ADC_5 - case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break; + case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break; case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break; #endif #if HAS_TEMP_ADC_6 - case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break; + case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break; case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break; #endif #if HAS_TEMP_ADC_7 - case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break; + case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break; case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break; + case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break; case Measure_FILWIDTH: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else filwidth.accumulate(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else filwidth.accumulate(hal.adc_value()); break; #endif #if ENABLED(POWER_MONITOR_CURRENT) case Prepare_POWER_MONITOR_CURRENT: - HAL_START_ADC(POWER_MONITOR_CURRENT_PIN); + hal.adc_start(POWER_MONITOR_CURRENT_PIN); break; case Measure_POWER_MONITOR_CURRENT: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_current_sample(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_current_sample(hal.adc_value()); break; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) case Prepare_POWER_MONITOR_VOLTAGE: - HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN); + hal.adc_start(POWER_MONITOR_VOLTAGE_PIN); break; case Measure_POWER_MONITOR_VOLTAGE: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_voltage_sample(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_voltage_sample(hal.adc_value()); break; #endif #if HAS_JOY_ADC_X - case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break; + case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break; case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break; #endif #if HAS_JOY_ADC_Y - case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break; + case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break; case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break; #endif #if HAS_JOY_ADC_Z - case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break; + case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break; case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break; #endif @@ -3482,12 +3482,12 @@ void Temperature::isr() { #ifndef ADC_BUTTON_DEBOUNCE_DELAY #define ADC_BUTTON_DEBOUNCE_DELAY 16 #endif - case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break; + case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break; case Measure_ADC_KEY: - if (!HAL_ADC_READY()) + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // redo this state else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) { - raw_ADCKey_value = HAL_READ_ADC(); + raw_ADCKey_value = hal.adc_value(); if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) { NOMORE(current_ADCKey_raw, raw_ADCKey_value); ADCKey_count++; diff --git a/ini/native.ini b/ini/native.ini index fe5fe3a5d05a..eba34afc8394 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -34,14 +34,14 @@ src_filter = ${common.default_src_filter} + [simulator_common] platform = native framework = -build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g +build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip + MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} From a941cd33e290ed7268ac963388eb0cb28485cd72 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 23:47:52 -0600 Subject: [PATCH 20/32] =?UTF-8?q?=F0=9F=94=A8=20Configurable=20firmware=20?= =?UTF-8?q?bin=20filename?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Configuration.h > FIRMWARE_BIN --- buildroot/share/PlatformIO/scripts/marlin.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index b8a6283cedf1..4830232d0bc5 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -48,6 +48,15 @@ def encrypt_mks(source, target, env, new_name): 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] + # If FIRMWARE_BIN is defined by config, override all + import re + patt = re.compile("^\\s*#define\\s+FIRMWARE_BIN\\s+\"?(.+)\"?") + with open(join("Marlin", "Configuration.h")) as f: + for line in f: + m = patt.search(line) + if m != None: + new_name = m.group(1) + fwpath = target[0].path fwfile = open(fwpath, "rb") enfile = open(target[0].dir.path + "/" + new_name, "wb") From c74161c011abfeb7004631f63642566f37a845db Mon Sep 17 00:00:00 2001 From: fflosi <34758322+fflosi@users.noreply.github.com> Date: Sat, 25 Dec 2021 05:57:07 -0300 Subject: [PATCH 21/32] =?UTF-8?q?=E2=9C=A8=20Per-axis=20TMC=20hold=20multi?= =?UTF-8?q?plier=20(#23345)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 19 + Marlin/src/inc/Conditionals_post.h | 505 +++++++++++++++---------- Marlin/src/module/stepper/trinamic.cpp | 28 +- 3 files changed, 336 insertions(+), 216 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 3eb836ec6562..2410d8b9033f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2690,6 +2690,7 @@ #define X_RSENSE 0.11 #define X_CHAIN_POS -1 // -1..0: Not chained. 1: MCU MOSI connected. 2: Next in chain, ... //#define X_INTERPOLATE true // Enable to override 'INTERPOLATE' for the X axis + //#define X_HOLD_MULTIPLIER 0.5 // Enable to override 'HOLD_MULTIPLIER' for the X axis #endif #if AXIS_IS_TMC(X2) @@ -2699,6 +2700,7 @@ #define X2_RSENSE 0.11 #define X2_CHAIN_POS -1 //#define X2_INTERPOLATE true + //#define X2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y) @@ -2708,6 +2710,7 @@ #define Y_RSENSE 0.11 #define Y_CHAIN_POS -1 //#define Y_INTERPOLATE true + //#define Y_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y2) @@ -2717,6 +2720,7 @@ #define Y2_RSENSE 0.11 #define Y2_CHAIN_POS -1 //#define Y2_INTERPOLATE true + //#define Y2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z) @@ -2726,6 +2730,7 @@ #define Z_RSENSE 0.11 #define Z_CHAIN_POS -1 //#define Z_INTERPOLATE true + //#define Z_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z2) @@ -2735,6 +2740,7 @@ #define Z2_RSENSE 0.11 #define Z2_CHAIN_POS -1 //#define Z2_INTERPOLATE true + //#define Z2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z3) @@ -2744,6 +2750,7 @@ #define Z3_RSENSE 0.11 #define Z3_CHAIN_POS -1 //#define Z3_INTERPOLATE true + //#define Z3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z4) @@ -2753,6 +2760,7 @@ #define Z4_RSENSE 0.11 #define Z4_CHAIN_POS -1 //#define Z4_INTERPOLATE true + //#define Z4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(I) @@ -2762,6 +2770,7 @@ #define I_RSENSE 0.11 #define I_CHAIN_POS -1 //#define I_INTERPOLATE true + //#define I_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(J) @@ -2771,6 +2780,7 @@ #define J_RSENSE 0.11 #define J_CHAIN_POS -1 //#define J_INTERPOLATE true + //#define J_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(K) @@ -2780,6 +2790,7 @@ #define K_RSENSE 0.11 #define K_CHAIN_POS -1 //#define K_INTERPOLATE true + //#define K_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E0) @@ -2788,6 +2799,7 @@ #define E0_RSENSE 0.11 #define E0_CHAIN_POS -1 //#define E0_INTERPOLATE true + //#define E0_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E1) @@ -2796,6 +2808,7 @@ #define E1_RSENSE 0.11 #define E1_CHAIN_POS -1 //#define E1_INTERPOLATE true + //#define E1_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E2) @@ -2804,6 +2817,7 @@ #define E2_RSENSE 0.11 #define E2_CHAIN_POS -1 //#define E2_INTERPOLATE true + //#define E2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E3) @@ -2812,6 +2826,7 @@ #define E3_RSENSE 0.11 #define E3_CHAIN_POS -1 //#define E3_INTERPOLATE true + //#define E3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E4) @@ -2820,6 +2835,7 @@ #define E4_RSENSE 0.11 #define E4_CHAIN_POS -1 //#define E4_INTERPOLATE true + //#define E4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E5) @@ -2828,6 +2844,7 @@ #define E5_RSENSE 0.11 #define E5_CHAIN_POS -1 //#define E5_INTERPOLATE true + //#define E5_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E6) @@ -2836,6 +2853,7 @@ #define E6_RSENSE 0.11 #define E6_CHAIN_POS -1 //#define E6_INTERPOLATE true + //#define E6_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E7) @@ -2844,6 +2862,7 @@ #define E7_RSENSE 0.11 #define E7_CHAIN_POS -1 //#define E7_INTERPOLATE true + //#define E7_HOLD_MULTIPLIER 0.5 #endif /** diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 95c8f7737b31..a5c9d20eda9e 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1861,231 +1861,332 @@ #undef Z3_STALL_SENSITIVITY #undef Z4_STALL_SENSITIVITY #endif - #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) - #define X_SENSORLESS 1 - #endif - #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) - #define X2_SENSORLESS 1 - #endif - #if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y) - #define Y_SENSORLESS 1 - #endif - #if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2) - #define Y2_SENSORLESS 1 - #endif - #if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z) - #define Z_SENSORLESS 1 - #endif - #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) - #define Z2_SENSORLESS 1 - #endif - #if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3) - #define Z3_SENSORLESS 1 - #endif - #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) - #define Z4_SENSORLESS 1 - #endif - #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) - #define I_SENSORLESS 1 - #endif - #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) - #define J_SENSORLESS 1 - #endif - #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) - #define K_SENSORLESS 1 - #endif - #if AXIS_HAS_STEALTHCHOP(X) - #define X_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - #define X2_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - #define Y_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - #define Y2_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - #define Z_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - #define Z2_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - #define Z3_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - #define Z4_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(I) - #define I_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(J) - #define J_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(K) - #define K_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0) - #define E0_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - #define E1_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - #define E2_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - #define E3_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - #define E4_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - #define E5_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - #define E6_HAS_STEALTHCHOP 1 + #if AXIS_IS_TMC(X) + #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) + #define X_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X) + #define X_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define X_SPI_SENSORLESS X_SENSORLESS + #endif + #ifndef X_INTERPOLATE + #define X_INTERPOLATE INTERPOLATE + #endif + #ifndef X_HOLD_MULTIPLIER + #define X_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - #define E7_HAS_STEALTHCHOP 1 + + #if AXIS_IS_TMC(X2) + #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) + #define X2_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X2) + #define X2_HAS_STEALTHCHOP 1 + #endif + #ifndef X2_INTERPOLATE + #define X2_INTERPOLATE X_INTERPOLATE + #endif + #ifndef X2_HOLD_MULTIPLIER + #define X2_HOLD_MULTIPLIER X_HOLD_MULTIPLIER + #endif + #ifndef X2_SLAVE_ADDRESS + #define X2_SLAVE_ADDRESS 0 + #endif #endif - #if ENABLED(SPI_ENDSTOPS) - #define X_SPI_SENSORLESS X_SENSORLESS - #if HAS_Y_AXIS + #if AXIS_IS_TMC(Y) + #if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y) + #define Y_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y) + #define Y_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) #define Y_SPI_SENSORLESS Y_SENSORLESS #endif - #if HAS_Z_AXIS - #define Z_SPI_SENSORLESS Z_SENSORLESS + #ifndef Y_INTERPOLATE + #define Y_INTERPOLATE INTERPOLATE #endif - #if LINEAR_AXES >= 4 - #define I_SPI_SENSORLESS I_SENSORLESS + #ifndef Y_HOLD_MULTIPLIER + #define Y_HOLD_MULTIPLIER HOLD_MULTIPLIER #endif - #if LINEAR_AXES >= 5 - #define J_SPI_SENSORLESS J_SENSORLESS + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 0 #endif - #if LINEAR_AXES >= 6 - #define K_SPI_SENSORLESS K_SENSORLESS + #if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2) + #define Y2_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y2) + #define Y2_HAS_STEALTHCHOP 1 + #endif + #ifndef Y2_INTERPOLATE + #define Y2_INTERPOLATE Y_INTERPOLATE + #endif + #ifndef Y2_HOLD_MULTIPLIER + #define Y2_HOLD_MULTIPLIER Y_HOLD_MULTIPLIER + #endif + #ifndef Y2_SLAVE_ADDRESS + #define Y2_SLAVE_ADDRESS 0 + #endif #endif #endif - #ifndef X_INTERPOLATE - #define X_INTERPOLATE INTERPOLATE - #endif - #ifndef X2_INTERPOLATE - #define X2_INTERPOLATE INTERPOLATE - #endif - #ifndef Y_INTERPOLATE - #define Y_INTERPOLATE INTERPOLATE - #endif - #ifndef Y2_INTERPOLATE - #define Y2_INTERPOLATE INTERPOLATE - #endif - #ifndef Z_INTERPOLATE - #define Z_INTERPOLATE INTERPOLATE - #endif - #ifndef Z2_INTERPOLATE - #define Z2_INTERPOLATE INTERPOLATE - #endif - #ifndef Z3_INTERPOLATE - #define Z3_INTERPOLATE INTERPOLATE - #endif - #ifndef Z4_INTERPOLATE - #define Z4_INTERPOLATE INTERPOLATE - #endif - #if LINEAR_AXES >= 4 && !defined(I_INTERPOLATE) - #define I_INTERPOLATE INTERPOLATE - #endif - #if LINEAR_AXES >= 5 && !defined(J_INTERPOLATE) - #define J_INTERPOLATE INTERPOLATE - #endif - #if LINEAR_AXES >= 6 && !defined(K_INTERPOLATE) - #define K_INTERPOLATE INTERPOLATE - #endif - #ifndef E0_INTERPOLATE - #define E0_INTERPOLATE INTERPOLATE - #endif - #ifndef E1_INTERPOLATE - #define E1_INTERPOLATE INTERPOLATE - #endif - #ifndef E2_INTERPOLATE - #define E2_INTERPOLATE INTERPOLATE - #endif - #ifndef E3_INTERPOLATE - #define E3_INTERPOLATE INTERPOLATE - #endif - #ifndef E4_INTERPOLATE - #define E4_INTERPOLATE INTERPOLATE - #endif - #ifndef E5_INTERPOLATE - #define E5_INTERPOLATE INTERPOLATE - #endif - #ifndef E6_INTERPOLATE - #define E6_INTERPOLATE INTERPOLATE - #endif - #ifndef E7_INTERPOLATE - #define E7_INTERPOLATE INTERPOLATE - #endif - #ifndef X_SLAVE_ADDRESS - #define X_SLAVE_ADDRESS 0 - #endif - #ifndef Y_SLAVE_ADDRESS - #define Y_SLAVE_ADDRESS 0 - #endif - #ifndef Z_SLAVE_ADDRESS - #define Z_SLAVE_ADDRESS 0 - #endif - #ifndef I_SLAVE_ADDRESS - #define I_SLAVE_ADDRESS 0 - #endif - #ifndef J_SLAVE_ADDRESS - #define J_SLAVE_ADDRESS 0 - #endif - #ifndef K_SLAVE_ADDRESS - #define K_SLAVE_ADDRESS 0 - #endif - #ifndef X2_SLAVE_ADDRESS - #define X2_SLAVE_ADDRESS 0 - #endif - #ifndef Y2_SLAVE_ADDRESS - #define Y2_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(Z) + #if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z) + #define Z_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z) + #define Z_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define Z_SPI_SENSORLESS Z_SENSORLESS + #endif + #ifndef Z_INTERPOLATE + #define Z_INTERPOLATE INTERPOLATE + #endif + #ifndef Z_HOLD_MULTIPLIER + #define Z_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 0 + #endif + #if NUM_Z_STEPPER_DRIVERS >= 2 + #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) + #define Z2_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z2) + #define Z2_HAS_STEALTHCHOP 1 + #endif + #ifndef Z2_INTERPOLATE + #define Z2_INTERPOLATE Z_INTERPOLATE + #endif + #ifndef Z2_HOLD_MULTIPLIER + #define Z2_HOLD_MULTIPLIER Z_HOLD_MULTIPLIER + #endif + #ifndef Z2_SLAVE_ADDRESS + #define Z2_SLAVE_ADDRESS 0 + #endif + #endif + #if NUM_Z_STEPPER_DRIVERS >= 3 + #if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3) + #define Z3_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z3) + #define Z3_HAS_STEALTHCHOP 1 + #endif + #ifndef Z3_INTERPOLATE + #define Z3_INTERPOLATE Z_INTERPOLATE + #endif + #ifndef Z3_HOLD_MULTIPLIER + #define Z3_HOLD_MULTIPLIER Z_HOLD_MULTIPLIER + #endif + #ifndef Z3_SLAVE_ADDRESS + #define Z3_SLAVE_ADDRESS 0 + #endif + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) + #define Z4_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z4) + #define Z4_HAS_STEALTHCHOP 1 + #endif + #ifndef Z4_INTERPOLATE + #define Z4_INTERPOLATE Z_INTERPOLATE + #endif + #ifndef Z4_HOLD_MULTIPLIER + #define Z4_HOLD_MULTIPLIER Z_HOLD_MULTIPLIER + #endif + #ifndef Z4_SLAVE_ADDRESS + #define Z4_SLAVE_ADDRESS 0 + #endif + #endif #endif - #ifndef Z2_SLAVE_ADDRESS - #define Z2_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(I) + #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) + #define I_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(I) + #define I_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define I_SPI_SENSORLESS I_SENSORLESS + #endif + #ifndef I_INTERPOLATE + #define I_INTERPOLATE INTERPOLATE + #endif + #ifndef I_HOLD_MULTIPLIER + #define I_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef I_SLAVE_ADDRESS + #define I_SLAVE_ADDRESS 0 + #endif #endif - #ifndef Z3_SLAVE_ADDRESS - #define Z3_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(J) + #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) + #define J_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(J) + #define J_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define J_SPI_SENSORLESS J_SENSORLESS + #endif + #ifndef J_INTERPOLATE + #define J_INTERPOLATE INTERPOLATE + #endif + #ifndef J_HOLD_MULTIPLIER + #define J_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef J_SLAVE_ADDRESS + #define J_SLAVE_ADDRESS 0 + #endif #endif - #ifndef Z4_SLAVE_ADDRESS - #define Z4_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(K) + #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) + #define K_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(K) + #define K_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define K_SPI_SENSORLESS K_SENSORLESS + #endif + #ifndef K_INTERPOLATE + #define K_INTERPOLATE INTERPOLATE + #endif + #ifndef K_HOLD_MULTIPLIER + #define K_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef K_SLAVE_ADDRESS + #define K_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E0_SLAVE_ADDRESS - #define E0_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(E0) + #if AXIS_HAS_STEALTHCHOP(E0) + #define E0_HAS_STEALTHCHOP 1 + #endif + #ifndef E0_INTERPOLATE + #define E0_INTERPOLATE INTERPOLATE + #endif + #ifndef E0_HOLD_MULTIPLIER + #define E0_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E1_SLAVE_ADDRESS - #define E1_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E1) + #if AXIS_HAS_STEALTHCHOP(E1) + #define E1_HAS_STEALTHCHOP 1 + #endif + #ifndef E1_INTERPOLATE + #define E1_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E1_HOLD_MULTIPLIER + #define E1_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E1_SLAVE_ADDRESS + #define E1_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E2_SLAVE_ADDRESS - #define E2_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E2) + #if AXIS_HAS_STEALTHCHOP(E2) + #define E2_HAS_STEALTHCHOP 1 + #endif + #ifndef E2_INTERPOLATE + #define E2_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E2_HOLD_MULTIPLIER + #define E2_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E2_SLAVE_ADDRESS + #define E2_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E3_SLAVE_ADDRESS - #define E3_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E3) + #if AXIS_HAS_STEALTHCHOP(E3) + #define E3_HAS_STEALTHCHOP 1 + #endif + #ifndef E3_INTERPOLATE + #define E3_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E3_HOLD_MULTIPLIER + #define E3_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E3_SLAVE_ADDRESS + #define E3_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E4_SLAVE_ADDRESS - #define E4_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E4) + #if AXIS_HAS_STEALTHCHOP(E4) + #define E4_HAS_STEALTHCHOP 1 + #endif + #ifndef E4_INTERPOLATE + #define E4_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E4_HOLD_MULTIPLIER + #define E4_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E4_SLAVE_ADDRESS + #define E4_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E5_SLAVE_ADDRESS - #define E5_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E5) + #if AXIS_HAS_STEALTHCHOP(E5) + #define E5_HAS_STEALTHCHOP 1 + #endif + #ifndef E5_INTERPOLATE + #define E5_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E5_HOLD_MULTIPLIER + #define E5_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E5_SLAVE_ADDRESS + #define E5_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E6_SLAVE_ADDRESS - #define E6_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E6) + #if AXIS_HAS_STEALTHCHOP(E6) + #define E6_HAS_STEALTHCHOP 1 + #endif + #ifndef E6_INTERPOLATE + #define E6_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E6_HOLD_MULTIPLIER + #define E6_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E6_SLAVE_ADDRESS + #define E6_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E7_SLAVE_ADDRESS - #define E7_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E7) + #if AXIS_HAS_STEALTHCHOP(E7) + #define E7_HAS_STEALTHCHOP 1 + #endif + #ifndef E7_INTERPOLATE + #define E7_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E7_HOLD_MULTIPLIER + #define E7_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E7_SLAVE_ADDRESS + #define E7_SLAVE_ADDRESS 0 + #endif #endif -#endif +#endif // HAS_TRINAMIC_CONFIG #if ANY_AXIS_HAS(HW_SERIAL) #define HAS_TMC_HW_SERIAL 1 diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index e8ecbf1c762a..7baa2108f06a 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -38,7 +38,7 @@ enum StealthIndex : uint8_t { LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K) }; -#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE) +#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE, ST##_HOLD_MULTIPLIER) // IC = TMC model number // ST = Stepper object letter @@ -200,7 +200,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -212,7 +212,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -235,7 +235,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -247,7 +247,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -604,7 +604,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2208) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -622,7 +622,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -646,7 +646,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2209) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -664,7 +664,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -688,7 +688,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2660) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); TMC2660_n::CHOPCONF_t chopconf{0}; @@ -710,7 +710,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC5130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -722,7 +722,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -745,7 +745,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC5160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -757,7 +757,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current From fca6d12093e0cadc0c95a0e4cabfd560e6b628a1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 03:27:45 -0600 Subject: [PATCH 22/32] =?UTF-8?q?=F0=9F=94=A7=20Move=20MOTHERBOARD=20close?= =?UTF-8?q?r=20to=20top?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index c425746bb5d1..f0fc4dd7d608 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -94,6 +94,11 @@ // @section machine +// Choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_RAMPS_14_EFB +#endif + /** * 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. @@ -137,11 +142,6 @@ // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH -// Choose the name from boards.h that matches your setup -#ifndef MOTHERBOARD - #define MOTHERBOARD BOARD_RAMPS_14_EFB -#endif - // Name displayed in the LCD "Ready" message and Info menu //#define CUSTOM_MACHINE_NAME "3D Printer" From bdb071688e7a2e1eb900c26c59c20bca847ccfdc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 26 Dec 2021 01:09:46 +0000 Subject: [PATCH 23/32] [cron] Bump distribution date (2021-12-26) --- 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 596e910a1f61..fca302288f67 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-12-25" +//#define STRING_DISTRIBUTION_DATE "2021-12-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b43547ef53c1..d2b7a9377565 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 "2021-12-25" + #define STRING_DISTRIBUTION_DATE "2021-12-26" #endif /** From 4f0932e5c1647b00efff22a2a5f30a1fdd57cc19 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 20:00:48 -0600 Subject: [PATCH 24/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20`freeMemory`=20endle?= =?UTF-8?q?ss=20loop?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23295 --- Marlin/src/HAL/AVR/HAL.h | 2 +- Marlin/src/HAL/DUE/HAL.h | 2 +- Marlin/src/HAL/LINUX/HAL.h | 2 +- Marlin/src/HAL/LPC1768/HAL.h | 2 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 2 +- Marlin/src/HAL/SAMD51/HAL.h | 2 +- Marlin/src/HAL/STM32/HAL.h | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 +- 11 files changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 9babe2d60352..682374b4ac84 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -205,7 +205,7 @@ class MarlinHAL { static inline void clear_reset_source() { MCUSR = 0; } // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 0dd123acdd51..5d1d2cf236d7 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -196,7 +196,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 0bd8635c9045..c1b7a5499706 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -126,7 +126,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index ba0729590f5b..f1cdbe6f078d 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -219,7 +219,7 @@ class MarlinHAL { static void clear_reset_source(); // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index bfbdaf211ff3..0798bdde393d 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -228,7 +228,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 144bf9c08dfa..9fcd73e9b64b 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -176,7 +176,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index d71ccd796b2f..c23ddf69bdaa 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -226,7 +226,7 @@ class MarlinHAL { static void clear_reset_source(); // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 517c8f2cb808..8fb4c9299ff5 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -270,7 +270,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index fdf914b1b02e..a5f67a50f0aa 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -155,7 +155,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 5506599cdf03..8ca76dc6368b 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -160,7 +160,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 4a0b5688d77c..10263ecb394a 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -182,7 +182,7 @@ class MarlinHAL { static void clear_reset_source(); // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods From d7af6199362f35db72579e16843239087689e145 Mon Sep 17 00:00:00 2001 From: kaidegit <60053077+kaidegit@users.noreply.github.com> Date: Sun, 26 Dec 2021 10:12:20 +0800 Subject: [PATCH 25/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20open=20for=20bin=20r?= =?UTF-8?q?ename=20(#23351)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/marlin.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 4830232d0bc5..2114a05fb388 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -51,7 +51,7 @@ def encrypt_mks(source, target, env, new_name): # If FIRMWARE_BIN is defined by config, override all import re patt = re.compile("^\\s*#define\\s+FIRMWARE_BIN\\s+\"?(.+)\"?") - with open(join("Marlin", "Configuration.h")) as f: + with open(join("Marlin", "Configuration.h"), encoding="utf-8") as f: for line in f: m = patt.search(line) if m != None: From 57315f02cbacea6a90c56349dc7e571e53692740 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 21:25:47 -0600 Subject: [PATCH 26/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20missing=20ADC=20meth?= =?UTF-8?q?od?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/DUE/HAL.h | 2 -- Marlin/src/HAL/ESP32/HAL.h | 3 --- Marlin/src/HAL/LINUX/HAL.h | 1 - Marlin/src/HAL/LPC1768/HAL.h | 2 -- Marlin/src/HAL/NATIVE_SIM/HAL.h | 1 - Marlin/src/HAL/SAMD51/HAL.h | 2 -- Marlin/src/HAL/STM32/HAL.h | 4 +--- Marlin/src/HAL/STM32F1/HAL.h | 2 -- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 -- Marlin/src/HAL/TEENSY35_36/HAL.h | 2 -- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 -- 11 files changed, 1 insertion(+), 22 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 5d1d2cf236d7..96a59fcf3cbe 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -131,8 +131,6 @@ typedef Servo hal_servo_t; #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ANALOG_SELECT(ch) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 361c9032317d..138346b950a7 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -85,9 +85,6 @@ void noTone(const pin_t _pin); void analogWrite(pin_t pin, int value); -// ADC -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index c1b7a5499706..a2a9692cbdcd 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -82,7 +82,6 @@ extern MSerialT usb_serial; // ADC #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) // ------------------------ // Class Utilities diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index f1cdbe6f078d..e1ade3d9a72c 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -133,8 +133,6 @@ extern DefaultSerial1 USBSerial; #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -#define HAL_ANALOG_SELECT(pin) hal.adc_enable(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 0798bdde393d..50da5af2eb92 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -117,7 +117,6 @@ extern MSerialT serial_stream_3; #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) /* ---------------- Delay in cycles */ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 9fcd73e9b64b..e9d4a70c3f19 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -106,8 +106,6 @@ typedef Servo hal_servo_t; // ADC // -#define HAL_ANALOG_SELECT(pin) - //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index c23ddf69bdaa..f9bf1c938aa5 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -142,8 +142,6 @@ typedef libServo hal_servo_t; // ADC // ------------------------ -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) - #ifdef ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION #else @@ -240,7 +238,7 @@ class MarlinHAL { } // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t pin); + static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT); } // Begin ADC sampling on the given channel static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 8fb4c9299ff5..bdbf4a1885ae 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -188,8 +188,6 @@ extern uint16_t HAL_adc_result; // ADC // ------------------------ -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); - #ifdef ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION #else diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index a5f67a50f0aa..0661b55f53a9 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -105,8 +105,6 @@ uint32_t __get_PRIMASK(void); // CMSIS #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 8ca76dc6368b..1cc465c4bbf2 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -110,8 +110,6 @@ typedef int8_t pin_t; #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 10263ecb394a..7bad14317909 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -129,8 +129,6 @@ typedef int8_t pin_t; #define HAL_ADC_RESOLUTION 10 #define HAL_ADC_FILTERED // turn off ADC oversampling -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // From a47f559db15ad550930f0d49d352e73852ff900d Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Sun, 26 Dec 2021 10:36:09 +0700 Subject: [PATCH 27/32] =?UTF-8?q?=F0=9F=90=9B=20HAL=20refactor=20followup?= =?UTF-8?q?=20(#23354)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/SAMD51/HAL.h | 2 +- Marlin/src/HAL/STM32/HAL_SPI.cpp | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index e9d4a70c3f19..a88ed9ba7988 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -186,7 +186,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const uint8_t ch); + static inline void adc_enable(const uint8_t ch) {} // Begin ADC sampling on the given channel static void adc_start(const pin_t pin); diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 7737245de85b..40d320d5e822 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -104,7 +104,7 @@ static SPISettings spiConfig; uint8_t spiRec() { hal.isr_off(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - hal.isr_off(); // Enable interrupts + hal.isr_on(); // Enable interrupts return data; } diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index bdbf4a1885ae..9b973c3ea4fe 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -280,7 +280,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t pin); + static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); } // Begin ADC sampling on the given channel static void adc_start(const pin_t pin); diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 0661b55f53a9..14f463708bce 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -163,7 +163,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t ch); + static inline void adc_enable(const pin_t ch) {} // Begin ADC sampling on the given channel static void adc_start(const pin_t ch); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 7bad14317909..b7a807028163 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -192,7 +192,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t pin); + static inline void adc_enable(const pin_t pin) {} // Begin ADC sampling on the given channel static void adc_start(const pin_t pin); From 555c749fe2be922eaf3bd78a79ae3b89b012662f Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 25 Dec 2021 19:41:01 -0800 Subject: [PATCH 28/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20Robin=20E3=20N?= =?UTF-8?q?eoPixel=20pin=20default=20(#23350)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index c30bb0ac9e99..e02d1db7863d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -64,11 +64,6 @@ #define Z_MIN_PROBE_PIN PB1 #endif -// LED driving pin -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PA2 -#endif - // // Steppers // @@ -245,6 +240,11 @@ #endif #endif +// LED driving pin +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA2 +#endif + // // SD Card // From 00e6e90648012ca0b954139f867a9a0201319209 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 22:10:47 -0600 Subject: [PATCH 29/32] =?UTF-8?q?=F0=9F=90=9B=20Fix=20adc=5Fstart=20for=20?= =?UTF-8?q?AVR,=20native?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23295 --- Marlin/src/HAL/AVR/HAL.h | 10 ++++++---- Marlin/src/HAL/LINUX/HAL.h | 2 +- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 682374b4ac84..3dade7fa1558 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -229,12 +229,14 @@ class MarlinHAL { } // Begin ADC sampling on the given channel - static inline void adc_start(const pin_t ch) { + static inline void adc_start(const uint8_t ch) { #ifdef MUX5 - if (ch > 7) { ADCSRB = _BV(MUX5); return; } + ADCSRB = ch > 7 ? _BV(MUX5) : 0; + #else + ADCSRB = 0; #endif - ADCSRB = 0; - ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC); + ADMUX = _BV(REFS0) | (ch & 0x07); + SBI(ADCSRA, ADSC); } // Is the ADC ready for reading? diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index a2a9692cbdcd..104c47ec6123 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -140,7 +140,7 @@ class MarlinHAL { static inline void adc_enable(const uint8_t) {} // Begin ADC sampling on the given channel - static inline void adc_start(const pin_t ch) { active_ch = ch; } + static inline void adc_start(const uint8_t ch) { active_ch = ch; } // Is the ADC ready for reading? static inline bool adc_ready() { return true; } From 6a8b9274a31d11c396ce1bc44b3a0b872a4606dc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 23:15:17 -0600 Subject: [PATCH 30/32] =?UTF-8?q?=E2=8F=AA=EF=B8=8F=20Refactor=20still=20n?= =?UTF-8?q?eeds=20work?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Reverting #23295 --- Marlin/src/HAL/AVR/HAL.cpp | 14 +- Marlin/src/HAL/AVR/HAL.h | 172 ++++++++------------- Marlin/src/HAL/AVR/MarlinSerial.cpp | 4 +- Marlin/src/HAL/AVR/fast_pwm.cpp | 11 +- Marlin/src/HAL/AVR/timers.h | 4 +- Marlin/src/HAL/DUE/HAL.cpp | 45 ++++-- Marlin/src/HAL/DUE/HAL.h | 134 ++++++---------- Marlin/src/HAL/DUE/MarlinSerial.cpp | 4 +- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/HAL.cpp | 35 ++--- Marlin/src/HAL/ESP32/HAL.h | 145 +++++++----------- Marlin/src/HAL/ESP32/timers.h | 4 +- Marlin/src/HAL/LINUX/HAL.cpp | 39 +++-- Marlin/src/HAL/LINUX/HAL.h | 144 ++++++------------ Marlin/src/HAL/LINUX/arduino.cpp | 4 +- Marlin/src/HAL/LINUX/include/Arduino.h | 5 +- Marlin/src/HAL/LINUX/timers.h | 4 +- Marlin/src/HAL/LPC1768/HAL.cpp | 42 ++--- Marlin/src/HAL/LPC1768/HAL.h | 160 +++++++------------ Marlin/src/HAL/LPC1768/Servo.h | 3 +- Marlin/src/HAL/LPC1768/fast_pwm.cpp | 14 +- Marlin/src/HAL/LPC1768/main.cpp | 6 +- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 172 ++++++++------------- Marlin/src/HAL/NATIVE_SIM/timers.h | 4 +- Marlin/src/HAL/SAMD51/HAL.cpp | 26 ++-- Marlin/src/HAL/SAMD51/HAL.h | 127 ++++++---------- Marlin/src/HAL/STM32/HAL.cpp | 28 ++-- Marlin/src/HAL/STM32/HAL.h | 177 ++++++++++----------- Marlin/src/HAL/STM32/HAL_SPI.cpp | 8 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 8 +- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 +- Marlin/src/HAL/STM32/pinsDebug.h | 6 +- Marlin/src/HAL/STM32/timers.h | 4 +- Marlin/src/HAL/STM32F1/HAL.cpp | 190 ++++++++++++----------- Marlin/src/HAL/STM32F1/HAL.h | 184 ++++++++++------------ Marlin/src/HAL/STM32F1/Servo.h | 3 +- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 8 +- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.cpp | 79 +++++----- Marlin/src/HAL/TEENSY31_32/HAL.h | 131 +++++----------- Marlin/src/HAL/TEENSY31_32/timers.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.cpp | 110 +++++++------- Marlin/src/HAL/TEENSY35_36/HAL.h | 133 +++++----------- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.cpp | 194 ++++++++++++------------ Marlin/src/HAL/TEENSY40_41/HAL.h | 148 ++++++------------ Marlin/src/HAL/TEENSY40_41/timers.h | 2 +- Marlin/src/HAL/shared/HAL.cpp | 36 ----- Marlin/src/HAL/shared/HAL_spi_L6470.cpp | 8 +- Marlin/src/MarlinCore.cpp | 48 +++--- Marlin/src/feature/caselight.cpp | 2 +- Marlin/src/feature/controllerfan.cpp | 2 +- Marlin/src/feature/e_parser.h | 4 +- Marlin/src/feature/leds/leds.cpp | 2 +- Marlin/src/feature/spindle_laser.cpp | 10 +- Marlin/src/feature/spindle_laser.h | 2 +- Marlin/src/gcode/control/M42.cpp | 4 +- Marlin/src/gcode/gcode_d.cpp | 10 +- Marlin/src/inc/SanityCheck.h | 7 - Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 4 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/servo.cpp | 2 +- Marlin/src/module/servo.h | 2 +- Marlin/src/module/stepper.cpp | 10 +- Marlin/src/module/temperature.cpp | 112 +++++++------- ini/native.ini | 4 +- 69 files changed, 1279 insertions(+), 1749 deletions(-) delete mode 100644 Marlin/src/HAL/shared/HAL.cpp diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 2b6d2bdbcf07..d7bf2a6f6fbb 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -36,7 +36,7 @@ // ------------------------ // Don't initialize/override variable (which would happen in .init4) -uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); +uint8_t reset_reason __attribute__((section(".noinit"))); // ------------------------ // Public functions @@ -45,22 +45,22 @@ uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); __attribute__((naked)) // Don't output function pro- and epilogue __attribute__((used)) // Output the function, even if "not used" __attribute__((section(".init3"))) // Put in an early user definable section -void save_reset_reason() { +void HAL_save_reset_reason() { #if ENABLED(OPTIBOOT_RESET_REASON) __asm__ __volatile__( A("STS %0, r2") - : "=m"(hal.reset_reason) + : "=m"(reset_reason) ); #else - hal.reset_reason = MCUSR; + reset_reason = MCUSR; #endif // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop - hal.clear_reset_source(); + MCUSR = 0; wdt_disable(); } -void MarlinHAL::init() { +void HAL_init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 @@ -77,7 +77,7 @@ void MarlinHAL::init() { #endif } -void MarlinHAL::reboot() { +void HAL_reboot() { #if ENABLED(USE_WATCHDOG) while (1) { /* run out the watchdog */ } #else diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 3dade7fa1558..2217f239d64e 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -74,8 +74,9 @@ #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END() SREG = _sreg #endif - -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +#define ISRS_ENABLED() TEST(SREG, SREG_I) +#define ENABLE_ISRS() sei() +#define DISABLE_ISRS() cli() // ------------------------ // Types @@ -83,16 +84,16 @@ typedef int8_t pin_t; -// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS - -class Servo; -typedef Servo hal_servo_t; +#define HAL_SERVO_LIB Servo // ------------------------ -// Serial ports +// Public Variables // ------------------------ +extern uint8_t reset_reason; + +// Serial ports #ifdef USBCON #include "../../core/serial_hook.h" typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; @@ -141,31 +142,20 @@ typedef Servo hal_servo_t; #endif #endif -// -// ADC -// -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +// ------------------------ +// Public functions +// ------------------------ -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +void HAL_init(); -#define HAL_SENSITIVE_PINS 0, 1, +//void cli(); -#ifdef __AVR_AT90USB1286__ - #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) -#endif +//void _delay_ms(const int delay); -// AVR compatibility -#define strtof strtod +inline void HAL_clear_reset_source() { } +inline uint8_t HAL_get_reset_source() { return reset_reason; } -// ------------------------ -// Class Utilities -// ------------------------ +void HAL_reboot(); #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -176,91 +166,63 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: +// ADC +#ifdef DIDR2 + #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0) +#else + #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind); +#endif - // Earliest possible init, before setup() - MarlinHAL() {} +inline void HAL_adc_init() { + ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; + DIDR0 = 0; + #ifdef DIDR2 + DIDR2 = 0; + #endif +} - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 +#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC) +#ifdef MUX5 + #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch) +#else + #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch) +#endif - static inline bool isr_state() { return TEST(SREG, SREG_I); } - static inline void isr_on() { sei(); } - static inline void isr_off() { cli(); } +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_READ_ADC() ADC +#define HAL_ADC_READY() !TEST(ADCSRA, ADSC) - static inline void delay_ms(const int ms) { _delay_ms(ms); } +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - // Tasks, called from idle() - static inline void idletask() {} +#define HAL_SENSITIVE_PINS 0, 1, - // Reset - static uint8_t reset_reason; - static inline uint8_t get_reset_source() { return reset_reason; } - static inline void clear_reset_source() { MCUSR = 0; } +#ifdef __AVR_AT90USB1286__ + #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) +#endif - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } +// AVR compatibility +#define strtof strtod - // - // ADC Methods - // +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment - // Called by Temperature::init once at startup - static inline void adc_init() { - ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; - DIDR0 = 0; - #ifdef DIDR2 - DIDR2 = 0; - #endif - } +/** + * set_pwm_frequency + * Sets the frequency of the timer corresponding to the provided pin + * as close as possible to the provided desired frequency. Internally + * calculates the required waveform generation mode, prescaler and + * resolution values required and sets the timer registers accordingly. + * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) + * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) + */ +void set_pwm_frequency(const pin_t pin, int f_desired); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const uint8_t ch) { - #ifdef DIDR2 - if (ch > 7) { SBI(DIDR2, ch & 0x07); return; } - #endif - SBI(DIDR0, ch); - } - - // Begin ADC sampling on the given channel - static inline void adc_start(const uint8_t ch) { - #ifdef MUX5 - ADCSRB = ch > 7 ? _BV(MUX5) : 0; - #else - ADCSRB = 0; - #endif - ADMUX = _BV(REFS0) | (ch & 0x07); - SBI(ADCSRA, ADSC); - } - - // Is the ADC ready for reading? - static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); } - - // The current value of the ADC register - static inline __typeof__(ADC) adc_value() { return ADC; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); - - /** - * Set the frequency of the timer for the given pin as close as - * possible to the provided desired frequency. Internally calculate - * the required waveform generation mode, prescaler, and resolution - * values and set timer registers accordingly. - * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) - * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); -}; - -extern MarlinHAL hal; +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 986462437c8f..cd8bf5e6903b 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -486,7 +486,7 @@ void MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -534,7 +534,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !B_TXC) { diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 0053b44c3c7b..804e5fad3070 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -35,9 +35,10 @@ struct Timer { }; /** - * Get the timer information and register for a pin. - * Return a Timer struct containing this information. - * Used by set_pwm_frequency, set_pwm_duty + * get_pwm_timer + * Get the timer information and register of the provided pin. + * Return a Timer struct containing this information. + * Used by set_pwm_frequency, set_pwm_duty */ Timer get_pwm_timer(const pin_t pin) { uint8_t q = 0; @@ -149,7 +150,7 @@ Timer get_pwm_timer(const pin_t pin) { return timer; } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { +void set_pwm_frequency(const pin_t pin, int f_desired) { Timer timer = get_pwm_timer(pin); if (timer.n == 0) return; // Don't proceed if protected timer or not recognized uint16_t size; @@ -229,7 +230,7 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { #endif // NEEDS_HARDWARE_PWM -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { #if NEEDS_HARDWARE_PWM // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index e1fcbf52d6d8..36b04eae0d1f 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) /* 18 cycles maximum latency */ #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 20b711b1b05e..a3985652e71d 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -34,7 +34,7 @@ // Public Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; // ------------------------ // Public functions @@ -42,7 +42,8 @@ uint16_t MarlinHAL::adc_result; TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void MarlinHAL::init() { +// HAL initialization task +void HAL_init() { // Initialize the USB stack #if ENABLED(SDSUPPORT) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up @@ -51,17 +52,21 @@ void MarlinHAL::init() { TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } -void MarlinHAL::init_board() { - #ifdef BOARD_INIT - BOARD_INIT(); - #endif +// HAL idle task +void HAL_idletask() { + // Perform USB stack housekeeping + usb_task_idle(); } -void MarlinHAL::idletask() { - usb_task_idle(); // Perform USB stack housekeeping -} +// Disable interrupts +void cli() { noInterrupts(); } + +// Enable interrupts +void sei() { interrupts(); } + +void HAL_clear_reset_source() { } -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch ((RSTC->RSTC_SR >> 8) & 0x07) { case 0: return RST_POWER_ON; case 1: return RST_BACKUP; @@ -72,7 +77,12 @@ uint8_t MarlinHAL::get_reset_source() { } } -void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); } +void HAL_reboot() { rstc_start_software_reset(RSTC); } + +void _delay_ms(const int delay_ms) { + // Todo: port for Due? + delay(delay_ms); +} extern "C" { extern unsigned int _ebss; // end of bss section @@ -84,6 +94,19 @@ int freeMemory() { return (int)&free_memory - (heap_end ?: (int)&_ebss); } +// ------------------------ +// ADC +// ------------------------ + +void HAL_adc_start_conversion(const uint8_t ch) { + HAL_adc_result = analogRead(ch); +} + +uint16_t HAL_adc_get_result() { + // nop + return HAL_adc_result; +} + // Forward the default serial ports #if USING_HW_SERIAL0 DefaultSerial1 MSerial0(false, Serial); diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 96a59fcf3cbe..96ab5d9808ac 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -38,10 +38,6 @@ #include "../../core/serial_hook.h" -// ------------------------ -// Serial ports -// ------------------------ - typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; @@ -101,38 +97,60 @@ extern DefaultSerial4 MSerial3; #include "MarlinSerial.h" #include "MarlinSerialUSB.h" -// ------------------------ -// Types -// ------------------------ +// On AVR this is in math.h? +#define square(x) ((x)*(x)) typedef int8_t pin_t; -// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS -class Servo; -typedef Servo hal_servo_t; +#define HAL_SERVO_LIB Servo // // Interrupts // -#define sei() noInterrupts() -#define cli() interrupts() +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() + +void cli(); // Disable interrupts +void sei(); // Enable interrupts + +void HAL_clear_reset_source(); // clear reset reason +uint8_t HAL_get_reset_source(); // get reset reason -#define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off() -#define CRITICAL_SECTION_END() if (_irqon) hal.isr_on() +void HAL_reboot(); // // ADC // -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +extern uint16_t HAL_adc_result; // result of last ADC conversion #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif +#define HAL_ANALOG_SELECT(ch) + +inline void HAL_adc_init() {}//todo + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true + +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); + // -// Pin Mapping for M42, M43, M226 +// PWM +// +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// +// Pin Map // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -141,18 +159,27 @@ typedef Servo hal_servo_t; // // Tone // +void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// ------------------------ -// Class Utilities -// ------------------------ +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +void HAL_idletask(); +void HAL_init(); + +// +// Utility functions +// +void _delay_ms(const int delay); #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif +int freeMemory(); + #pragma GCC diagnostic pop #ifdef __cplusplus @@ -162,70 +189,3 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s #ifdef __cplusplus } #endif - -// Return free RAM between end of heap (or end bss) and whatever is current -int freeMemory(); - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static void init_board(); // Called less early in setup() - static void reboot(); // Software reset - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint16_t adc_result; - - // Called by Temperature::init once at startup - static inline void adc_init() {} - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const int ch) {} - - // Begin ADC sampling on the given channel - static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); } - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - static inline uint16_t adc_value() { return adc_result; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * No inverting the duty cycle in this HAL. - * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 638f7a100722..fe62ff5607d5 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -406,7 +406,7 @@ size_t MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -454,7 +454,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) { diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index bcfd07e268c5..e2932ff36f91 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 604acae8dd5b..810e386894ec 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -52,7 +52,7 @@ // Externs // ------------------------ -portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; +portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; // ------------------------ // Local defines @@ -64,7 +64,7 @@ portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; // Public Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; // ------------------------ // Private Variables @@ -95,22 +95,20 @@ volatile int numPWMUsed = 0, #endif #if ENABLED(USE_ESP32_EXIO) - HardwareSerial YSerial2(2); void Write_EXIO(uint8_t IO, uint8_t v) { - if (hal.isr_state()) { - hal.isr_off(); + if (ISRS_ENABLED()) { + DISABLE_ISRS(); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); - hal.isr_on(); + ENABLE_ISRS(); } else YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); } - #endif -void MarlinHAL::init_board() { +void HAL_init_board() { #if ENABLED(USE_ESP32_TASK_WDT) esp_task_wdt_init(10, true); #endif @@ -156,24 +154,27 @@ void MarlinHAL::init_board() { #endif } -void MarlinHAL::idletask() { +void HAL_idletask() { #if BOTH(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); } -uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } +void HAL_clear_reset_source() { } + +uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } -void MarlinHAL::reboot() { ESP.restart(); } +void HAL_reboot() { ESP.restart(); } + +void _delay_ms(int delay_ms) { delay(delay_ms); } // return free memory between end of heap (or end bss) and whatever is current -int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } +int freeMemory() { return ESP.getFreeHeap(); } // ------------------------ // ADC // ------------------------ - #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL adc1_channel_t get_channel(int pin) { @@ -195,7 +196,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) { } } -void MarlinHAL::adc_init() { +void HAL_adc_init() { // Configure ADC adc1_config_width(ADC_WIDTH_12Bit); @@ -225,11 +226,11 @@ void MarlinHAL::adc_init() { } } -void MarlinHAL::adc_start(const pin_t pin) { - const adc1_channel_t chan = get_channel(pin); +void HAL_adc_start_conversion(const uint8_t adc_pin) { + const adc1_channel_t chan = get_channel(adc_pin); uint32_t mv; esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); - adc_result = mv * 1023.0 / 3300.0; + HAL_adc_result = mv * 1023.0 / 3300.0; // Change the attenuation level based on the new reading adc_atten_t atten; diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 138346b950a7..8473e3c4e469 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -49,6 +49,8 @@ // Defines // ------------------------ +extern portMUX_TYPE spinlock; + #define MYSERIAL1 flushableSerial #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -63,6 +65,9 @@ #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) +#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL) +#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock) +#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock) // ------------------------ // Types @@ -70,8 +75,14 @@ typedef int16_t pin_t; -class Servo; -typedef Servo hal_servo_t; +#define HAL_SERVO_LIB Servo + +// ------------------------ +// Public Variables +// ------------------------ + +/** result of last ADC conversion */ +extern uint16_t HAL_adc_result; // ------------------------ // Public functions @@ -80,18 +91,59 @@ typedef Servo hal_servo_t; // // Tone // +void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); +// clear reset reason +void HAL_clear_reset_source(); + +// reset reason +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +void _delay_ms(int delay); + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + void analogWrite(pin_t pin, int value); -// -// Pin Mapping for M42, M43, M226 -// +// ADC +#define HAL_ANALOG_SELECT(pin) + +void HAL_adc_init(); + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true + +void HAL_adc_start_conversion(const uint8_t adc_pin); + +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Pin Map #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +#define BOARD_INIT() HAL_init_board(); +void HAL_idletask(); +inline void HAL_init() {} +void HAL_init_board(); + #if ENABLED(USE_ESP32_EXIO) void Write_EXIO(uint8_t IO, uint8_t v); #endif @@ -136,86 +188,3 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) { } } - -// ------------------------ -// Class Utilities -// ------------------------ - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - -void _delay_ms(const int ms); - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static void init_board(); // Called less early in setup() - static void reboot(); // Restart the firmware - - static portMUX_TYPE spinlock; - static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; } - static inline void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); } - static inline void isr_off() { portENTER_CRITICAL(&spinlock); } - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static int freeMemory(); - - // - // ADC Methods - // - - static uint16_t adc_result; - - // Called by Temperature::init once at startup - static void adc_init(); - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) {} - - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - static inline uint16_t adc_value() { return adc_result; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * No inverting the duty cycle in this HAL. - * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index efae594f6cd8..266169848daf 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -136,5 +136,5 @@ 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); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index 91739aaa7b06..0b679170ef17 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -24,12 +24,6 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" -extern MarlinHAL hal; - -// ------------------------ -// Serial ports -// ------------------------ - MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); // U8glib required functions @@ -43,21 +37,42 @@ extern "C" { //************************// // return free heap space -int freeMemory() { return 0; } +int freeMemory() { + return 0; +} // ------------------------ // ADC // ------------------------ -uint8_t MarlinHAL::active_ch = 0; +void HAL_adc_init() { -uint16_t MarlinHAL::adc_value() { - const pin_t pin = analogInputToDigitalPin(active_ch); +} + +void HAL_adc_enable_channel(const uint8_t ch) { + +} + +uint8_t active_ch = 0; +void HAL_adc_start_conversion(const uint8_t ch) { + active_ch = ch; +} + +bool HAL_adc_finished() { + return true; +} + +uint16_t HAL_adc_get_result() { + pin_t pin = analogInputToDigitalPin(active_ch); if (!VALID_PIN(pin)) return 0; - const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); + uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); return data; // return 10bit value as Marlin expects } -void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } +void HAL_pwm_init() { + +} + +void HAL_reboot() { /* Reset the application state and GPIO */ } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 104c47ec6123..d7d3a92b73b9 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -21,42 +21,25 @@ */ #pragma once -#include -#include -#include -#undef min -#undef max -#include - -#include "hardware/Clock.h" - -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" -#include "fastio.h" -#include "watchdog.h" -#include "serial.h" - -// ------------------------ -// Defines -// ------------------------ - #define CPU_32_BIT -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp #define F_CPU 100000000UL #define SystemCoreClock F_CPU +#include +#include +#include -#define DELAY_CYCLES(x) Clock::delayCycles(x) +#undef min +#undef max -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 +#include -void _printf(const char *format, ...); +void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); +//extern "C" volatile uint32_t _millis; + //arduino: Print.h #define DEC 10 #define HEX 16 @@ -66,27 +49,36 @@ uint8_t _getc(); #define B01 1 #define B10 2 -// ------------------------ -// Serial ports -// ------------------------ +#include "hardware/Clock.h" + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +#define SHARED_SERVOS HAS_SERVOS extern MSerialT usb_serial; #define MYSERIAL1 usb_serial +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + // // Interrupts // #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() +#define ISRS_ENABLED() +#define ENABLE_ISRS() +#define DISABLE_ISRS() -// ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 - -// ------------------------ -// Class Utilities -// ------------------------ +inline void HAL_init() {} +// Utility functions #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -96,67 +88,29 @@ int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Reset the application state and GPIO - - static inline bool isr_state() { return true; } - static inline void isr_on() {} - static inline void isr_off() {} - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static constexpr uint8_t reset_reason = RST_POWER_ON; - static inline uint8_t get_reset_source() { return reset_reason; } - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint8_t active_ch; - - // Called by Temperature::init once at startup - static inline void adc_init() {} - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const uint8_t) {} - - // Begin ADC sampling on the given channel - static inline void adc_start(const uint8_t ch) { active_ch = ch; } +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +void HAL_adc_init(); +void HAL_adc_enable_channel(const uint8_t ch); +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); - // The current value of the ADC register - static uint16_t adc_value(); +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to change the resolution or invert the duty cycle. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +// Reset source +inline void HAL_clear_reset_source(void) {} +inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } - static inline void set_pwm_frequency(const pin_t, int) {} -}; +void HAL_reboot(); // Reset the application state and GPIO -extern MarlinHAL hal; +/* ---------------- Delay in cycles */ +FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { + Clock::delayCycles(x); +} diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 075b4ccde2f4..4b56d02a389c 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -31,7 +31,9 @@ void cli() { } // Disable void sei() { } // Enable // Time functions -void _delay_ms(const int ms) { delay(ms); } +void _delay_ms(const int delay_ms) { + delay(delay_ms); +} uint32_t millis() { return (uint32_t)Clock::millis(); diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index 49e04d0cb7d3..d4086e259a2f 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -59,6 +59,7 @@ typedef uint8_t byte; #endif #define sq(v) ((v) * (v)) +#define square(v) sq(v) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) //Interrupts @@ -73,8 +74,8 @@ extern "C" { } // Time functions -extern "C" void delay(const int ms); -void _delay_ms(const int ms); +extern "C" void delay(const int milis); +void _delay_ms(const int delay); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2d2a95774c1b..a98ceb6f391d 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -92,5 +92,5 @@ 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); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 541848b08acc..cee9cfc5f744 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -31,7 +31,7 @@ DefaultSerial1 USBSerial(false, UsbSerial); -uint32_t MarlinHAL::adc_result = 0; +uint32_t HAL_adc_reading = 0; // U8glib required functions extern "C" { @@ -41,6 +41,8 @@ extern "C" { void u8g_Delay(uint16_t val) { delay(val); } } +//************************// + // return free heap space int freeMemory() { char stack_end; @@ -52,33 +54,33 @@ int freeMemory() { return result; } -void MarlinHAL::reboot() { NVIC_SystemReset(); } - -uint8_t MarlinHAL::get_reset_source() { - #if ENABLED(USE_WATCHDOG) - if (watchdog_timed_out()) return RST_WATCHDOG; - #endif - return RST_POWER_ON; -} - -void MarlinHAL::clear_reset_source() { - TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); +// scan command line for code +// return index into pin map array if found and the pin is valid. +// return dval if not found or not a valid pin. +int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { + const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; + const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; + return ind > -1 ? ind : dval; } void flashFirmware(const int16_t) { delay(500); // Give OS time to disconnect USB_Connect(false); // USB clear connection delay(1000); // Give OS time to notice - hal.reboot(); + HAL_reboot(); } -// For M42/M43, scan command line for pin code -// return index into pin map array if found and the pin is valid. -// return dval if not found or not a valid pin. -int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { - const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; - const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; - return ind > -1 ? ind : dval; +void HAL_clear_reset_source(void) { + TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); } +uint8_t HAL_get_reset_source(void) { + #if ENABLED(USE_WATCHDOG) + if (watchdog_timed_out()) return RST_WATCHDOG; + #endif + return RST_POWER_ON; +} + +void HAL_reboot() { NVIC_SystemReset(); } + #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index e1ade3d9a72c..348ea6b21a04 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -28,6 +28,8 @@ #define CPU_32_BIT +void HAL_init(); + #include #include #include @@ -45,9 +47,12 @@ extern "C" volatile uint32_t _millis; #include #include -// ------------------------ -// Serial ports -// ------------------------ +// +// Default graphical display delays +// +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; @@ -109,12 +114,26 @@ extern DefaultSerial1 USBSerial; // // Interrupts // +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() + +// +// Utility functions +// +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() +int freeMemory(); + +#pragma GCC diagnostic pop // -// ADC +// ADC API // #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift), @@ -133,9 +152,20 @@ extern DefaultSerial1 USBSerial; #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -// -// Pin Mapping for M42, M43, M226 -// +using FilteredADC = LPC176x::ADC; +extern uint32_t HAL_adc_reading; +[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) { + HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits +} +[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() { + return HAL_adc_reading; +} + +#define HAL_adc_init() +#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() (true) // Test whether the pin is valid constexpr bool VALID_PIN(const pin_t pin) { @@ -162,104 +192,32 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, -// ------------------------ -// Defines -// ------------------------ +#define HAL_IDLETASK 1 +void HAL_idletask(); #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -// Default graphical display delays -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// ------------------------ -// Class Utilities -// ------------------------ - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static uint8_t get_reset_source(); - static void clear_reset_source(); - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - using FilteredADC = LPC176x::ADC; - - // Called by Temperature::init once at startup - static inline void adc_init() {} - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) { - FilteredADC::enable_channel(pin); - } - - // Begin ADC sampling on the given pin - static uint32_t adc_result; - FORCE_INLINE static void adc_start(const pin_t pin) { - adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits - } - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - FORCE_INLINE static uint16_t adc_value() { - return (uint16_t)adc_result; - } +/** + * set_pwm_frequency + * Set the frequency of the timer corresponding to the provided pin + * All Hardware PWM pins run at the same frequency and all + * Software PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); - /** - * Set the frequency of the timer corresponding to the provided pin - * All Hardware PWM pins will run at the same frequency and - * All Software PWM pins will run at the same frequency - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); -}; +// Reset source +void HAL_clear_reset_source(void); +uint8_t HAL_get_reset_source(void); -extern MarlinHAL hal; +void HAL_reboot(); diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index f02f503a67da..eb12fd20f4d8 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -65,5 +65,4 @@ class libServo: public Servo { } }; -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index 91e92a157501..eae0e36b0b0e 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -21,17 +21,21 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" #include -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; if (LPC176x::pwm_attach_pin(pin)) LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { - LPC176x::pwm_set_frequency(pin, f_desired); -} +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM + + void set_pwm_frequency(const pin_t pin, int f_desired) { + LPC176x::pwm_set_frequency(pin, f_desired); + } + +#endif #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 419c99793fb8..ef0dc42c78ca 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void MarlinHAL::init() { +void HAL_init() { // Init LEDs #if PIN_EXISTS(LED) @@ -130,7 +130,7 @@ void MarlinHAL::init() { const millis_t usb_timeout = millis() + 2000; while (!USB_Configuration && PENDING(millis(), usb_timeout)) { delay(50); - idletask(); + HAL_idletask(); #if PIN_EXISTS(LED) TOGGLE(LED_PIN); // Flash quickly during USB initialization #endif @@ -142,7 +142,7 @@ void MarlinHAL::init() { } // HAL idle task -void MarlinHAL::idletask() { +void HAL_idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index c6d7bc632e2e..78e856db2857 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 50da5af2eb92..436b4b4daa26 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -21,10 +21,18 @@ */ #pragma once +#define CPU_32_BIT +#define HAL_IDLETASK +void HAL_idletask(); + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU #include #include + #undef min #undef max + #include #include "pinmapping.h" @@ -32,6 +40,8 @@ void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); +//extern "C" volatile uint32_t _millis; + //arduino: Print.h #define DEC 10 #define HEX 16 @@ -48,23 +58,7 @@ uint8_t _getc(); #include "watchdog.h" #include "serial.h" -// ------------------------ -// Defines -// ------------------------ - -#define CPU_32_BIT -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp - -#define F_CPU 100000000 -#define SystemCoreClock F_CPU - -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// ------------------------ -// Serial ports -// ------------------------ +#define SHARED_SERVOS HAS_SERVOS extern MSerialT serial_stream_0; extern MSerialT serial_stream_1; @@ -104,19 +98,49 @@ extern MSerialT serial_stream_3; #endif #endif -// ------------------------ -// Interrupts -// ------------------------ +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// +// Interrupts +// #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() +#define ISRS_ENABLED() +#define ENABLE_ISRS() +#define DISABLE_ISRS() -// ------------------------ -// ADC -// ------------------------ +inline void HAL_init() {} + +// Utility functions +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +int freeMemory(); +#pragma GCC diagnostic pop +// ADC #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true + +void HAL_adc_init(); +void HAL_adc_enable_channel(const uint8_t ch); +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); + +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Reset source +inline void HAL_clear_reset_source(void) {} +inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + +void HAL_reboot(); /* ---------------- Delay in cycles */ @@ -135,22 +159,29 @@ constexpr inline std::size_t strlen_constexpr(const char* str) { // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 if (str != nullptr) { std::size_t i = 0; - while (str[i] != '\0') ++i; + while (str[i] != '\0') { + ++i; + } + return i; } + return 0; } constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 - if (lhs == nullptr || rhs == nullptr) + if (lhs == nullptr || rhs == nullptr) { return rhs != nullptr ? -1 : 1; + } - for (std::size_t i = 0; i < count; ++i) + for (std::size_t i = 0; i < count; ++i) { if (lhs[i] != rhs[i]) { return lhs[i] < rhs[i] ? -1 : 1; - else if (lhs[i] == '\0') + } else if (lhs[i] == '\0') { return 0; + } + } return 0; } @@ -162,11 +193,14 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe do { char sc = {}; do { - if ((sc = *str++) == '\0') return nullptr; + if ((sc = *str++) == '\0') { + return nullptr; + } } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } + return str; } @@ -177,88 +211,12 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) { do { char sc = {}; do { - if ((sc = *str++) == '\0') return nullptr; + if ((sc = *str++) == '\0') { + return nullptr; + } } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } return str; } - -// ------------------------ -// Class Utilities -// ------------------------ - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return true; } - static inline void isr_on() {} - static inline void isr_off() {} - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static constexpr uint8_t reset_reason = RST_POWER_ON; - static inline uint8_t get_reset_source() { return reset_reason; } - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint8_t active_ch; - - // Called by Temperature::init once at startup - static void adc_init(); - - // Called by Temperature::init for each sensor at startup - static void adc_enable(const uint8_t ch); - - // Begin ADC sampling on the given channel - static void adc_start(const uint8_t ch); - - // Is the ADC ready for reading? - static bool adc_ready(); - - // The current value of the ADC register - static uint16_t adc_value(); - - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index be38d583b686..cedfdb62d631 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -87,5 +87,5 @@ 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); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index f0383251283d..8baad31bc751 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -106,7 +106,7 @@ // Private Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; #if ADC_IS_REQUIRED @@ -402,7 +402,7 @@ uint16_t MarlinHAL::adc_result; // ------------------------ // HAL initialization task -void MarlinHAL::init() { +void HAL_init() { TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) @@ -412,9 +412,17 @@ void MarlinHAL::init() { #endif } +// HAL idle task +/* +void HAL_idletask() { +} +*/ + +void HAL_clear_reset_source() { } + #pragma push_macro("WDT") #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { RSTC_RCAUSE_Type resetCause; resetCause.reg = REG_RSTC_RCAUSE; @@ -428,7 +436,7 @@ uint8_t MarlinHAL::get_reset_source() { } #pragma pop_macro("WDT") -void MarlinHAL::reboot() { NVIC_SystemReset(); } +void HAL_reboot() { NVIC_SystemReset(); } extern "C" { void * _sbrk(int incr); @@ -446,7 +454,7 @@ int freeMemory() { // ADC // ------------------------ -void MarlinHAL::adc_init() { +void HAL_adc_init() { #if ADC_IS_REQUIRED memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values @@ -483,17 +491,17 @@ void MarlinHAL::adc_init() { #endif // ADC_IS_REQUIRED } -void MarlinHAL::adc_start(const pin_t pin) { +void HAL_adc_start_conversion(const uint8_t adc_pin) { #if ADC_IS_REQUIRED LOOP_L_N(pi, COUNT(adc_pins)) { - if (pin == adc_pins[pi]) { - adc_result = HAL_adc_results[pi]; + if (adc_pin == adc_pins[pi]) { + HAL_adc_result = HAL_adc_results[pi]; return; } } #endif - adc_result = 0xFFFF; + HAL_adc_result = 0xFFFF; } #endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index a88ed9ba7988..c262752a8d66 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -89,29 +89,51 @@ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp -class Servo; -typedef Servo hal_servo_t; +#define SHARED_SERVOS HAS_SERVOS +#define HAL_SERVO_LIB Servo // // Interrupts // -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -#define cli() __disable_irq() // Disable interrupts -#define sei() __enable_irq() // Enable interrupts +#define cli() __disable_irq() // Disable interrupts +#define sei() __enable_irq() // Enable interrupts + +void HAL_clear_reset_source(); // clear reset reason +uint8_t HAL_get_reset_source(); // get reset reason + +void HAL_reboot(); // // ADC // +extern uint16_t HAL_adc_result; // Most recent ADC conversion + +#define HAL_ANALOG_SELECT(pin) + +void HAL_adc_init(); //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true + +void HAL_adc_start_conversion(const uint8_t adc_pin); // -// Pin Mapping for M42, M43, M226 +// PWM +// +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// +// Pin Map // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -120,92 +142,35 @@ typedef Servo hal_servo_t; // // Tone // +void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// ------------------------ -// Class Utilities -// ------------------------ +// Enable hooks into idle and setup for HAL +void HAL_init(); +/* +#define HAL_IDLETASK 1 +void HAL_idletask(); +*/ + +// +// Utility functions +// +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif +int freeMemory(); + +#pragma GCC diagnostic pop + #ifdef __cplusplus extern "C" { #endif - char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); - -extern "C" int freeMemory(); - #ifdef __cplusplus } #endif - -#pragma GCC diagnostic pop - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { sei(); } - static inline void isr_off() { cli(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint16_t adc_result; - - // Called by Temperature::init once at startup - static void adc_init(); - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const uint8_t ch) {} - - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - static uint16_t adc_value() { return adc_result; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 324a78316a2d..0920a72ec1bc 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -53,18 +53,16 @@ // Public Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; // ------------------------ // Public functions // ------------------------ -#if ENABLED(POSTMORTEM_DEBUGGING) - extern void install_min_serial(); -#endif +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); // HAL initialization task -void MarlinHAL::init() { +void HAL_init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. @@ -105,7 +103,7 @@ void MarlinHAL::init() { } // HAL idle task -void MarlinHAL::idletask() { +void HAL_idletask() { #if HAS_SHARED_MEDIA // Stm32duino currently doesn't have a "loop/idle" method CDC_resume_receive(); @@ -113,9 +111,9 @@ void MarlinHAL::idletask() { #endif } -void MarlinHAL::reboot() { NVIC_SystemReset(); } +void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { return #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : @@ -139,14 +137,24 @@ uint8_t MarlinHAL::get_reset_source() { ; } -void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } +void HAL_reboot() { NVIC_SystemReset(); } + +void _delay_ms(const int delay_ms) { delay(delay_ms); } extern "C" { extern unsigned int _ebss; // end of bss section } +// ------------------------ +// ADC +// ------------------------ + +// TODO: Make sure this doesn't cause any delay +void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } +uint16_t HAL_adc_get_result() { return HAL_adc_result; } + // Reset the system to initiate a firmware flash -WEAK void flashFirmware(const int16_t) { hal.reboot(); } +WEAK void flashFirmware(const int16_t) { HAL_reboot(); } // Maple Compatibility volatile uint32_t systick_uptime_millis = 0; diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index f9bf1c938aa5..adaf14223f32 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -44,9 +44,9 @@ #define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_3 340 -// ------------------------ -// Serial ports -// ------------------------ +// +// Serial Ports +// #ifdef USBCON #include #include "../../core/serial_hook.h" @@ -115,14 +115,17 @@ #define analogInputToDigitalPin(p) (p) #endif -// -// Interrupts -// -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() #define cli() __disable_irq() #define sei() __enable_irq() +// On AVR this is in math.h? +#define square(x) ((x)*(x)) + // ------------------------ // Types // ------------------------ @@ -133,61 +136,43 @@ typedef int16_t pin_t; #endif -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() // ------------------------ -// ADC +// Public Variables // ------------------------ -#ifdef ADC_RESOLUTION - #define HAL_ADC_RESOLUTION ADC_RESOLUTION -#else - #define HAL_ADC_RESOLUTION 12 -#endif - -#define HAL_ADC_VREF 3.3 +// result of last ADC conversion +extern uint16_t HAL_adc_result; -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +// ------------------------ +// Public functions +// ------------------------ -#ifdef STM32F1xx - #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) - #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) - #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG -#endif +// Memory related +#define __bss_end __bss_end__ -#define PLATFORM_M997_SUPPORT -void flashFirmware(const int16_t); +// Enable hooks into setup for HAL +void HAL_init(); +#define HAL_IDLETASK 1 +void HAL_idletask(); -// Maple Compatibility -typedef void (*systickCallback_t)(void); -void systick_attach_callback(systickCallback_t cb); -void HAL_SYSTICK_Callback(); +// Clear reset reason +void HAL_clear_reset_source(); -extern volatile uint32_t systick_uptime_millis; +// Reset reason +uint8_t HAL_get_reset_source(); -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +void HAL_reboot(); -// ------------------------ -// Class Utilities -// ------------------------ - -// Memory related -#define __bss_end __bss_end__ +void _delay_ms(const int delay); extern "C" char* _sbrk(int incr); #pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif +#pragma GCC diagnostic ignored "-Wunused-function" static inline int freeMemory() { volatile char top; @@ -196,72 +181,62 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { sei(); } - static inline void isr_off() { cli(); } - - static inline void delay_ms(const int ms) { delay(ms); } +// +// ADC +// - // Tasks, called from idle() - static void idletask(); +#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) - // Reset - static uint8_t get_reset_source(); - static void clear_reset_source(); +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } +#define HAL_ADC_VREF 3.3 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true - // - // ADC Methods - // +inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } - static uint16_t adc_result; +void HAL_adc_start_conversion(const uint8_t adc_pin); - // Called by Temperature::init once at startup - static inline void adc_init() { - analogReadResolution(HAL_ADC_RESOLUTION); - } +uint16_t HAL_adc_get_result(); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT); } +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } +#ifdef STM32F1xx + #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) + #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) + #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG +#endif - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +#define PLATFORM_M997_SUPPORT +void flashFirmware(const int16_t); - // The current value of the ADC register - static uint16_t adc_value() { return adc_result; } +// Maple Compatibility +typedef void (*systickCallback_t)(void); +void systick_attach_callback(systickCallback_t cb); +void HAL_SYSTICK_Callback(); - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +extern volatile uint32_t systick_uptime_millis; - /** - * Set the frequency of the timer for the given pin. - * All Timer PWM pins run at the same frequency. - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); +#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 + * All Timer PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); -extern MarlinHAL hal; +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 40d320d5e822..8ee476164785 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -102,9 +102,9 @@ static SPISettings spiConfig; // Soft SPI receive byte uint8_t spiRec() { - hal.isr_off(); // No interrupts during byte receive + DISABLE_ISRS(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts return data; } @@ -116,9 +116,9 @@ static SPISettings spiConfig; // Soft SPI send byte void spiSend(uint8_t data) { - hal.isr_off(); // No interrupts during byte send + DISABLE_ISRS(); // No interrupts during byte send HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts } // Soft SPI send block diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 7c8cc8dd21e1..252b057362c9 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -174,9 +174,9 @@ bool PersistentStore::access_finish() { UNLOCK_FLASH(); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - hal.isr_off(); + DISABLE_ISRS(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); - hal.isr_on(); + ENABLE_ISRS(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); @@ -229,9 +229,9 @@ bool PersistentStore::access_finish() { // output. Servo output still glitches with interrupts disabled, but recovers after the // erase. TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - hal.isr_off(); + DISABLE_ISRS(); eeprom_buffer_flush(); - hal.isr_on(); + ENABLE_ISRS(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index f6d0481c05c1..b1bea5ce20eb 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -29,7 +29,7 @@ // Array to support sticky frequency sets per timer static uint16_t timer_freq[TIMER_NUM]; -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); @@ -56,7 +56,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { +void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index a7f022a0b62d..73d850fc4313 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -115,6 +115,7 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(ANUM) port_print(ANUM) #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine +#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num // x is a variable used to search pin_array #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) @@ -122,11 +123,6 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin -// -// Pin Mapping for M43 -// -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num - #ifndef M43_NEVER_TOUCH #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) #ifdef KILL_PIN diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6828998198af..aad543229e16 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index efc513cf94d2..f29b30536146 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -79,7 +79,7 @@ #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ // ------------------------ -// Serial ports +// Public Variables // ------------------------ #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE @@ -112,21 +112,72 @@ #endif #endif +uint16_t HAL_adc_result; + // ------------------------ -// ADC +// Private Variables // ------------------------ +STM32ADC adc(ADC1); -uint16_t analogRead(pin_t pin) { - const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; - return is_analog ? analogRead(uint8_t(pin)) : 0; -} - -// Wrapper to maple unprotected analogWrite -void analogWrite(pin_t pin, int pwm_val8) { - if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); -} - -uint16_t MarlinHAL::adc_result; +const uint8_t adc_pins[] = { + #if HAS_TEMP_ADC_0 + TEMP_0_PIN, + #endif + #if HAS_TEMP_ADC_PROBE + TEMP_PROBE_PIN, + #endif + #if HAS_HEATED_BED + TEMP_BED_PIN, + #endif + #if HAS_TEMP_CHAMBER + TEMP_CHAMBER_PIN, + #endif + #if HAS_TEMP_COOLER + TEMP_COOLER_PIN, + #endif + #if HAS_TEMP_ADC_1 + TEMP_1_PIN, + #endif + #if HAS_TEMP_ADC_2 + TEMP_2_PIN, + #endif + #if HAS_TEMP_ADC_3 + TEMP_3_PIN, + #endif + #if HAS_TEMP_ADC_4 + TEMP_4_PIN, + #endif + #if HAS_TEMP_ADC_5 + TEMP_5_PIN, + #endif + #if HAS_TEMP_ADC_6 + TEMP_6_PIN, + #endif + #if HAS_TEMP_ADC_7 + TEMP_7_PIN, + #endif + #if ENABLED(FILAMENT_WIDTH_SENSOR) + FILWIDTH_PIN, + #endif + #if HAS_ADC_BUTTONS + ADC_KEYPAD_PIN, + #endif + #if HAS_JOY_ADC_X + JOY_X_PIN, + #endif + #if HAS_JOY_ADC_Y + JOY_Y_PIN, + #endif + #if HAS_JOY_ADC_Z + JOY_Z_PIN, + #endif + #if ENABLED(POWER_MONITOR_CURRENT) + POWER_MONITOR_CURRENT_PIN, + #endif + #if ENABLED(POWER_MONITOR_VOLTAGE) + POWER_MONITOR_VOLTAGE_PIN, + #endif +}; enum TempPinIndex : char { #if HAS_TEMP_ADC_0 @@ -194,16 +245,15 @@ uint16_t HAL_adc_results[ADC_PIN_COUNT]; // ------------------------ // Private functions // ------------------------ - static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ - reg_value = SCB->AIRCR; // read old register configuration - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); // Insert write key & priority group + (PriorityGroupTmp << 8)); /* Insert write key & priority group */ SCB->AIRCR = reg_value; } @@ -211,8 +261,6 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { // Public functions // ------------------------ -void flashFirmware(const int16_t) { hal.reboot(); } - // // Leave PA11/PA12 intact if USBSerial is not used // @@ -232,11 +280,7 @@ void flashFirmware(const int16_t) { hal.reboot(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -// ------------------------ -// MarlinHAL class -// ------------------------ - -void MarlinHAL::init() { +void HAL_init() { NVIC_SetPriorityGrouping(0x3); #if PIN_EXISTS(LED) OUT_WRITE(LED_PIN, LOW); @@ -255,7 +299,7 @@ void MarlinHAL::init() { } // HAL idle task -void MarlinHAL::idletask() { +void HAL_idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. @@ -270,7 +314,14 @@ void MarlinHAL::idletask() { #endif } -void MarlinHAL::reboot() { nvic_sys_reset(); } +void HAL_clear_reset_source() { } + +/** + * TODO: Check this and change or remove. + */ +uint8_t HAL_get_reset_source() { return RST_POWER_ON; } + +void _delay_ms(const int delay_ms) { delay(delay_ms); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -304,70 +355,11 @@ extern "C" { } */ +// ------------------------ // ADC - +// ------------------------ // Init the AD in continuous capture mode -void MarlinHAL::adc_init() { - static const uint8_t adc_pins[] = { - #if HAS_TEMP_ADC_0 - TEMP_0_PIN, - #endif - #if HAS_TEMP_ADC_PROBE - TEMP_PROBE_PIN, - #endif - #if HAS_HEATED_BED - TEMP_BED_PIN, - #endif - #if HAS_TEMP_CHAMBER - TEMP_CHAMBER_PIN, - #endif - #if HAS_TEMP_COOLER - TEMP_COOLER_PIN, - #endif - #if HAS_TEMP_ADC_1 - TEMP_1_PIN, - #endif - #if HAS_TEMP_ADC_2 - TEMP_2_PIN, - #endif - #if HAS_TEMP_ADC_3 - TEMP_3_PIN, - #endif - #if HAS_TEMP_ADC_4 - TEMP_4_PIN, - #endif - #if HAS_TEMP_ADC_5 - TEMP_5_PIN, - #endif - #if HAS_TEMP_ADC_6 - TEMP_6_PIN, - #endif - #if HAS_TEMP_ADC_7 - TEMP_7_PIN, - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - FILWIDTH_PIN, - #endif - #if HAS_ADC_BUTTONS - ADC_KEYPAD_PIN, - #endif - #if HAS_JOY_ADC_X - JOY_X_PIN, - #endif - #if HAS_JOY_ADC_Y - JOY_Y_PIN, - #endif - #if HAS_JOY_ADC_Z - JOY_Z_PIN, - #endif - #if ENABLED(POWER_MONITOR_CURRENT) - POWER_MONITOR_CURRENT_PIN, - #endif - #if ENABLED(POWER_MONITOR_VOLTAGE) - POWER_MONITOR_VOLTAGE_PIN, - #endif - }; - static STM32ADC adc(ADC1); +void HAL_adc_init() { // configure the ADC adc.calibrate(); #if F_CPU > 72000000 @@ -382,10 +374,10 @@ void MarlinHAL::adc_init() { adc.startConversion(); } -void MarlinHAL::adc_start(const pin_t pin) { +void HAL_adc_start_conversion(const uint8_t adc_pin) { //TEMP_PINS pin_index; TempPinIndex pin_index; - switch (pin) { + switch (adc_pin) { default: return; #if HAS_TEMP_ADC_0 case TEMP_0_PIN: pin_index = TEMP_0; break; @@ -448,4 +440,20 @@ void MarlinHAL::adc_start(const pin_t pin) { HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } +uint16_t HAL_adc_get_result() { return HAL_adc_result; } + +uint16_t analogRead(pin_t pin) { + const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; + return is_analog ? analogRead(uint8_t(pin)) : 0; +} + +// Wrapper to maple unprotected analogWrite +void analogWrite(pin_t pin, int pwm_val8) { + if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); +} + +void HAL_reboot() { nvic_sys_reset(); } + +void flashFirmware(const int16_t) { HAL_reboot(); } + #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 9b973c3ea4fe..153cfe8ac89e 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -66,10 +66,6 @@ #endif #endif -// ------------------------ -// Serial ports -// ------------------------ - #ifdef SERIAL_USB typedef ForwardSerial1Class< USBSerial > DefaultSerial1; extern DefaultSerial1 MSerial0; @@ -145,6 +141,11 @@ #endif #endif +// Set interrupt grouping for this MCU +void HAL_init(); +#define HAL_IDLETASK 1 +void HAL_idletask(); + /** * TODO: review this to return 1 for pins that are not analog input */ @@ -157,7 +158,15 @@ #define NO_COMPILE_TIME_PWM #endif -// Reset Reason +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() +#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() ((void)__iSeiRetVal()) +#define DISABLE_ISRS() ((void)__iCliRetVal()) + +// On AVR this is in math.h? +#define square(x) ((x)*(x)) + #define RST_POWER_ON 1 #define RST_EXTERNAL 2 #define RST_BROWN_OUT 4 @@ -172,67 +181,47 @@ typedef int8_t pin_t; -// Result of last ADC conversion -extern uint16_t HAL_adc_result; - // ------------------------ -// Interrupts +// Public Variables // ------------------------ -#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); (void)__iCliRetVal() -#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() -#define cli() noInterrupts() -#define sei() interrupts() +// Result of last ADC conversion +extern uint16_t HAL_adc_result; // ------------------------ -// ADC +// Public functions // ------------------------ -#ifdef ADC_RESOLUTION - #define HAL_ADC_RESOLUTION ADC_RESOLUTION -#else - #define HAL_ADC_RESOLUTION 12 -#endif - -#define HAL_ADC_VREF 3.3 +// Disable interrupts +#define cli() noInterrupts() -uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first -void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? +// Enable interrupts +#define sei() interrupts() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +// Memory related +#define __bss_end __bss_end__ -#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) -#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) +// Clear reset reason +void HAL_clear_reset_source(); -#define PLATFORM_M997_SUPPORT -void flashFirmware(const int16_t); +// Reset reason +uint8_t HAL_get_reset_source(); -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -#ifndef PWM_FREQUENCY - #define PWM_FREQUENCY 1000 // Default PWM Frequency -#endif +void HAL_reboot(); -// ------------------------ -// Class Utilities -// ------------------------ +void _delay_ms(const int delay); -// Memory related -#define __bss_end __bss_end__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" -void _delay_ms(const int ms); +/* +extern "C" { + int freeMemory(); +} +*/ extern "C" char* _sbrk(int incr); -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - static inline int freeMemory() { volatile char top; return &top - _sbrk(0); @@ -240,71 +229,58 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_primask(); } - static inline void isr_on() { ((void)__iSeiRetVal()); } - static inline void isr_off() { ((void)__iCliRetVal()); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static inline uint8_t get_reset_source() { return RST_POWER_ON; } - static inline void clear_reset_source() {} +// +// ADC +// - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } +#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); - // - // ADC Methods - // +void HAL_adc_init(); - static uint16_t adc_result; +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif - // Called by Temperature::init once at startup - static void adc_init(); +#define HAL_ADC_VREF 3.3 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); } +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); +uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first +void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - // The current value of the ADC register - static uint16_t adc_value() { return adc_result; } +#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) +#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] - * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false); +#define PLATFORM_M997_SUPPORT +void flashFirmware(const int16_t); - /** - * Set the frequency of the timer for the given pin. - * All Timer PWM pins run at the same frequency. - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); +#ifndef PWM_FREQUENCY + #define PWM_FREQUENCY 1000 // Default PWM Frequency +#endif +#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 + * All Timer PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); -extern MarlinHAL hal; +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index 745a1c93f07d..b6143de81d62 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -35,8 +35,7 @@ #define SERVO_DEFAULT_MIN_ANGLE 0 #define SERVO_DEFAULT_MAX_ANGLE 180 -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo class libServo { public: diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 11a1a107123e..98d56bc5e931 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -21,9 +21,11 @@ */ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" #include +#include "HAL.h" +#include "timers.h" #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) @@ -36,7 +38,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { return 0; } -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; timer_dev *timer; UNUSED(timer); @@ -49,7 +51,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { +void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer timer_dev *timer; UNUSED(timer); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 0cd807fc8479..f9ab6d13d374 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index b923ab77b1f1..f08cf799e9e8 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -31,10 +31,6 @@ #include -// ------------------------ -// Serial ports -// ------------------------ - #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -44,32 +40,33 @@ #endif USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ +uint16_t HAL_adc_result; -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) + 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 + 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) + 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. +}; - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } -} +/* + // disable interrupts + void cli() { noInterrupts(); } -// ------------------------ -// MarlinHAL Class -// ------------------------ + // enable interrupts + void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); +} -void MarlinHAL::reboot() { _reboot_Teensyduino_(); } +void HAL_clear_reset_source() { } -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -81,25 +78,25 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } -// ADC +void HAL_reboot() { _reboot_Teensyduino_(); } -void MarlinHAL::adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); -} +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void MarlinHAL::adc_start(const pin_t pin) { - static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) - 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 - 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) - 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. - }; - ADC0_SC1A = pin2sc1a[pin]; + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -uint16_t MarlinHAL::adc_value() { return ADC0_RA; } +void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; } + +uint16_t HAL_adc_get_result() { return ADC0_RA; } #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 14f463708bce..61d8b34604c5 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,9 +36,12 @@ #include -// ------------------------ -// Defines -// ------------------------ +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +//#undef MOTHERBOARD +//#define MOTHERBOARD BOARD_TEENSY31_32 #define IS_32BIT_TEENSY 1 #define IS_TEENSY_31_32 1 @@ -46,14 +49,6 @@ #define IS_TEENSY32 1 #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// ------------------------ -// Serial ports -// ------------------------ - #include "../../core/serial_hook.h" #define Serial0 Serial @@ -77,44 +72,31 @@ extern USBSerialType USBSerial; #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -// ------------------------ -// Types -// ------------------------ - -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo typedef int8_t pin_t; -// ------------------------ -// Interrupts -// ------------------------ - -uint32_t __get_PRIMASK(void); // CMSIS -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() - -// ------------------------ -// ADC -// ------------------------ - #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +inline void HAL_init() {} -// ------------------------ -// Class Utilities -// ------------------------ +// Clear the reset reason +void HAL_clear_reset_source(); + +// Get the reason for the reset +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -125,64 +107,27 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // +// ADC - // Called by Temperature::init once at startup - static void adc_init(); +void HAL_adc_init(); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t ch) {} +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Begin ADC sampling on the given channel - static void adc_start(const pin_t ch); +#define HAL_ANALOG_SELECT(pin) - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // The current value of the ADC register - static uint16_t adc_value(); +// PWM - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } -}; +// Pin Map -extern MarlinHAL hal; +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 9fcbb6f232c9..3b073d63ab29 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 54a5ad385536..046c00b56ed5 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -31,10 +31,6 @@ #include -// ------------------------ -// Serial ports -// ------------------------ - #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -43,34 +39,42 @@ USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +uint16_t HAL_adc_result, HAL_adc_select; + +static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 + 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only + 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 + 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only + 10+128, 11+128, // 49-50 are A23-A24 + 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only + 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only + 3, 19+128, // 64-65 are A10-A11 + 23, 23+128,// 66-67 are A21-A22 (DAC pins) + 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) + 26, // 70 is Temperature Sensor + 18+128 // 71 is Vref +}; + +/* + // disable interrupts + void cli() { noInterrupts(); } + + // enable interrupts + void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); } -// ------------------------ -// MarlinHAL Class -// ------------------------ +void HAL_clear_reset_source() { } -void MarlinHAL::reboot() { _reboot_Teensyduino_(); } - -// Reset - -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -82,49 +86,41 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } -// ADC +void HAL_reboot() { _reboot_Teensyduino_(); } -int8_t MarlinHAL::adc_select; +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void MarlinHAL::adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } - while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } - NVIC_ENABLE_IRQ(IRQ_FTM1); + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void MarlinHAL::adc_start(const pin_t adc_pin) { - static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 - 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only - 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 - 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only - 10+128, 11+128, // 49-50 are A23-A24 - 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only - 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only - 3, 19+128, // 64-65 are A10-A11 - 23, 23+128,// 66-67 are A21-A22 (DAC pins) - 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) - 26, // 70 is Temperature Sensor - 18+128 // 71 is Vref - }; +void HAL_adc_start_conversion(const uint8_t adc_pin) { const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - adc_select = -1; // Digital only + // Digital only + HAL_adc_select = -1; } else if (pin & 0x80) { - adc_select = 1; + HAL_adc_select = 1; ADC1_SC1A = pin & 0x7F; } else { - adc_select = 0; + HAL_adc_select = 0; ADC0_SC1A = pin; } } -uint16_t MarlinHAL::adc_value() { - switch (adc_select) { +uint16_t HAL_adc_get_result() { + switch (HAL_adc_select) { case 0: return ADC0_RA; case 1: return ADC1_RA; } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 1cc465c4bbf2..892eb2d3c5b8 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,6 +37,10 @@ #include #include +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + // ------------------------ // Defines // ------------------------ @@ -49,17 +53,6 @@ #define IS_TEENSY35 1 #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -#undef sq -#define sq(x) ((x)*(x)) - -// ------------------------ -// Serial ports -// ------------------------ - #include "../../core/serial_hook.h" #define Serial0 Serial @@ -83,43 +76,34 @@ extern USBSerialType USBSerial; #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -// ------------------------ -// Types -// ------------------------ - -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo typedef int8_t pin_t; -// ------------------------ -// Interrupts -// ------------------------ - -#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() - -// ------------------------ -// ADC -// ------------------------ - #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +#undef sq +#define sq(x) ((x)*(x)) -// ------------------------ -// Class Utilities -// ------------------------ +inline void HAL_init() {} + +// Clear reset reason +void HAL_clear_reset_source(); + +// Reset reason +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -130,66 +114,27 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return true; } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static int8_t adc_select; +// ADC - // Called by Temperature::init once at startup - static void adc_init(); +void HAL_adc_init(); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t) {} +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); +#define HAL_ANALOG_SELECT(pin) - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // The current value of the ADC register - static uint16_t adc_value(); +// PWM - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } -}; +// Pin Map -extern MarlinHAL hal; +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 8af79d73928e..6c342bbe0d25 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 68bd38f72ff8..270bee0dc9d4 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -33,10 +33,6 @@ #include "timers.h" #include -// ------------------------ -// Serial ports -// ------------------------ - #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -44,42 +40,75 @@ #endif USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -#define __bss_end _ebss - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - // Doesn't work on Teensy 4.x - uint32_t freeMemory() { - uint32_t free_memory; - free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); - return free_memory; - } +uint16_t HAL_adc_result, HAL_adc_select; + +static const uint8_t pin2sc1a[] = { + 0x07, // 0/A0 AD_B1_02 + 0x08, // 1/A1 AD_B1_03 + 0x0C, // 2/A2 AD_B1_07 + 0x0B, // 3/A3 AD_B1_06 + 0x06, // 4/A4 AD_B1_01 + 0x05, // 5/A5 AD_B1_00 + 0x0F, // 6/A6 AD_B1_10 + 0x00, // 7/A7 AD_B1_11 + 0x0D, // 8/A8 AD_B1_08 + 0x0E, // 9/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + 0x07, // 14/A0 AD_B1_02 + 0x08, // 15/A1 AD_B1_03 + 0x0C, // 16/A2 AD_B1_07 + 0x0B, // 17/A3 AD_B1_06 + 0x06, // 18/A4 AD_B1_01 + 0x05, // 19/A5 AD_B1_00 + 0x0F, // 20/A6 AD_B1_10 + 0x00, // 21/A7 AD_B1_11 + 0x0D, // 22/A8 AD_B1_08 + 0x0E, // 23/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + #ifdef ARDUINO_TEENSY41 + 0xFF, // 28 + 0xFF, // 29 + 0xFF, // 30 + 0xFF, // 31 + 0xFF, // 32 + 0xFF, // 33 + 0xFF, // 34 + 0xFF, // 35 + 0xFF, // 36 + 0xFF, // 37 + 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 + 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 + 0x09, // 40/A16 AD_B1_04 + 0x0A, // 41/A17 AD_B1_05 + #endif +}; + +/* +// disable interrupts +void cli() { noInterrupts(); } + +// enable interrupts +void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC1_GC & ADC_GC_CAL) ; + while (ADC2_GC & ADC_GC_CAL) ; } -// ------------------------ -// FastIO -// ------------------------ - -bool is_output(pin_t pin) { - const struct digital_pin_bitband_and_config_table_struct *p; - p = digital_pin_to_info_PGM + pin; - return (*(p->reg + 1) & p->mask); +void HAL_clear_reset_source() { + uint32_t reset_source = SRC_SRSR; + SRC_SRSR = reset_source; } -// ------------------------ -// MarlinHAL Class -// ------------------------ - -void MarlinHAL::reboot() { _reboot_Teensyduino_(); } - -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch (SRC_SRSR & 0xFF) { case 1: return RST_POWER_ON; break; case 2: return RST_SOFTWARE; break; @@ -92,92 +121,57 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } -void MarlinHAL::clear_reset_source() { - uint32_t reset_source = SRC_SRSR; - SRC_SRSR = reset_source; -} +void HAL_reboot() { _reboot_Teensyduino_(); } -// ADC +#define __bss_end _ebss -int8_t MarlinHAL::adc_select; +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void MarlinHAL::adc_init() { - analog_init(); - while (ADC1_GC & ADC_GC_CAL) { /* wait */ } - while (ADC2_GC & ADC_GC_CAL) { /* wait */ } + // Doesn't work on Teensy 4.x + uint32_t freeMemory() { + uint32_t free_memory; + if ((uint32_t)__brkval == 0) + free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end); + else + free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval); + return free_memory; + } } -void MarlinHAL::adc_start(const pin_t adc_pin) { - static const uint8_t pin2sc1a[] = { - 0x07, // 0/A0 AD_B1_02 - 0x08, // 1/A1 AD_B1_03 - 0x0C, // 2/A2 AD_B1_07 - 0x0B, // 3/A3 AD_B1_06 - 0x06, // 4/A4 AD_B1_01 - 0x05, // 5/A5 AD_B1_00 - 0x0F, // 6/A6 AD_B1_10 - 0x00, // 7/A7 AD_B1_11 - 0x0D, // 8/A8 AD_B1_08 - 0x0E, // 9/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - 0x07, // 14/A0 AD_B1_02 - 0x08, // 15/A1 AD_B1_03 - 0x0C, // 16/A2 AD_B1_07 - 0x0B, // 17/A3 AD_B1_06 - 0x06, // 18/A4 AD_B1_01 - 0x05, // 19/A5 AD_B1_00 - 0x0F, // 20/A6 AD_B1_10 - 0x00, // 21/A7 AD_B1_11 - 0x0D, // 22/A8 AD_B1_08 - 0x0E, // 23/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - #ifdef ARDUINO_TEENSY41 - 0xFF, // 28 - 0xFF, // 29 - 0xFF, // 30 - 0xFF, // 31 - 0xFF, // 32 - 0xFF, // 33 - 0xFF, // 34 - 0xFF, // 35 - 0xFF, // 36 - 0xFF, // 37 - 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 - 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 - 0x09, // 40/A16 AD_B1_04 - 0x0A, // 41/A17 AD_B1_05 - #endif - }; +void HAL_adc_start_conversion(const uint8_t adc_pin) { const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - adc_select = -1; // Digital only + HAL_adc_select = -1; // Digital only } else if (pin & 0x80) { - adc_select = 1; + HAL_adc_select = 1; ADC2_HC0 = pin & 0x7F; } else { - adc_select = 0; + HAL_adc_select = 0; ADC1_HC0 = pin; } } -uint16_t MarlinHAL::adc_value() { - switch (adc_select) { +uint16_t HAL_adc_get_result() { + switch (HAL_adc_select) { case 0: - while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ } + while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait return ADC1_R0; case 1: - while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ } + while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait return ADC2_R0; } return 0; } +bool is_output(pin_t pin) { + const struct digital_pin_bitband_and_config_table_struct *p; + p = digital_pin_to_info_PGM + pin; + return (*(p->reg + 1) & p->mask); +} + #endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index b7a807028163..2b730768a802 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,6 +41,10 @@ #include "../../feature/ethernet.h" #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + // ------------------------ // Defines // ------------------------ @@ -51,23 +55,7 @@ #define IS_TEENSY41 1 #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -#undef sq -#define sq(x) ((x)*(x)) - -// Don't place string constants in PROGMEM -#undef PSTR -#define PSTR(str) ({static const char *data = (str); &data[0];}) - -// ------------------------ -// Serial ports -// ------------------------ - #include "../../core/serial_hook.h" - #define Serial0 Serial #define _DECLARE_SERIAL(X) \ typedef ForwardSerial1Class DefaultSerial##X; \ @@ -101,47 +89,41 @@ extern USBSerialType USBSerial; #endif #endif -// ------------------------ -// Types -// ------------------------ - -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo typedef int8_t pin_t; -// ------------------------ -// Interrupts -// ------------------------ - -#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() - -// ------------------------ -// ADC -// ------------------------ - #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ADC_FILTERED // turn off ADC oversampling +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +#undef sq +#define sq(x) ((x)*(x)) -// FastIO -bool is_output(pin_t pin); +// Don't place string constants in PROGMEM +#undef PSTR +#define PSTR(str) ({static const char *data = (str); &data[0];}) -// ------------------------ -// Class Utilities -// ------------------------ +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +FORCE_INLINE void HAL_idletask() {} +FORCE_INLINE void HAL_init() {} + +// Clear reset reason +void HAL_clear_reset_source(); + +// Reset reason +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -152,66 +134,30 @@ extern "C" uint32_t freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_primask(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static void clear_reset_source(); - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // +// ADC - static int8_t adc_select; +void HAL_adc_init(); - // Called by Temperature::init once at startup - static void adc_init(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_FILTERED // turn off ADC oversampling +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) {} +#define HAL_ANALOG_SELECT(pin) - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +// PWM - // The current value of the ADC register - static uint16_t adc_value(); +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +// Pin Map -}; +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -extern MarlinHAL hal; +bool is_output(pin_t pin); diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 77fe0953d3bd..81cf67f7bc08 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); //void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/shared/HAL.cpp b/Marlin/src/HAL/shared/HAL.cpp deleted file mode 100644 index a5fe407188db..000000000000 --- a/Marlin/src/HAL/shared/HAL.cpp +++ /dev/null @@ -1,36 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2021 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 . - * - */ - -/** - * HAL/shared/HAL.cpp - */ - -#include "../../inc/MarlinConfig.h" - -MarlinHAL hal; - -#if ENABLED(SOFT_RESET_VIA_SERIAL) - - // Global for use by e_parser.h - void HAL_reboot() { hal.reboot(); } - -#endif diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp index 5d4ce89b2748..bd85dbe7bd7e 100644 --- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp +++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp @@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) { // First device in chain has data sent last extDigitalWrite(ss_pin, LOW); - hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t data_out = L6470_SpiTransfer_Mode_3(data); - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts extDigitalWrite(ss_pin, HIGH); return data_out; @@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain extDigitalWrite(ss_pin, LOW); for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted - hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP)); - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts if (i == chain_position) data_out = temp; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 009edeba2f58..5132d07e8711 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) { #endif // Run HAL idle tasks - hal.idletask(); + TERN_(HAL_IDLETASK, HAL_idletask()); // Check network connection TERN_(HAS_ETHERNET, ethernet.check()); @@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) { watchdog_refresh(); // Reboot the board - hal.reboot(); + HAL_reboot(); #else @@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() { * • L64XX Stepper Drivers (SPI) * • Stepper Driver Reset: DISABLE * • TMC Stepper Drivers (SPI) - * • Run hal.init_board() for additional pins setup + * • Run BOARD_INIT if defined * • ESP WiFi * - Get the Reset Reason and report it * - Print startup messages and diagnostics @@ -1119,8 +1119,8 @@ void setup() { tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable // Check startup - does nothing if bootloader sets MCUSR to 0 - const byte mcu = hal.get_reset_source(); - hal.clear_reset_source(); + const byte mcu = HAL_get_reset_source(); + HAL_clear_reset_source(); #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { @@ -1181,20 +1181,23 @@ void setup() { JTAGSWD_RESET(); #endif - // Disable any hardware debug to free up pins for IO - #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) delay(10); - SETUP_LOG("JTAGSWD_DISABLE"); - JTAGSWD_DISABLE(); - #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE) - delay(10); - SETUP_LOG("JTAG_DISABLE"); - JTAG_DISABLE(); + // Disable any hardware debug to free up pins for IO + #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + SETUP_LOG("JTAGSWD_DISABLE"); + JTAGSWD_DISABLE(); + #elif defined(JTAG_DISABLE) + SETUP_LOG("JTAG_DISABLE"); + JTAG_DISABLE(); + #else + #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." + #endif #endif TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime - SETUP_RUN(hal.init()); + SETUP_RUN(HAL_init()); // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) @@ -1240,16 +1243,19 @@ void setup() { SETUP_RUN(tmc_init_cs_pins()); #endif - SETUP_RUN(hal.init_board()); + #ifdef BOARD_INIT + SETUP_LOG("BOARD_INIT"); + BOARD_INIT(); + #endif SETUP_RUN(esp_wifi_init()); // Report Reset Reason - if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); - if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); + if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); + if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); - if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); - if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); + if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); + if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); @@ -1260,7 +1266,7 @@ void setup() { ); #endif SERIAL_ECHO_MSG(" Compiled: " __DATE__); - SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Some HAL need precise delay adjustment calibrate_delay_loop(); @@ -1532,7 +1538,7 @@ void setup() { #endif #if ENABLED(USE_WATCHDOG) - SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call + SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index a58cb66affc7..59832fd6edd7 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -69,7 +69,7 @@ void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS if (pin_is_pwm()) - hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( + set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct #else diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index f42bf52ae40a..59ba665e1114 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -76,7 +76,7 @@ void ControllerFan::update() { thermalManager.soft_pwm_controller_speed = speed; #else if (PWM_PIN(CONTROLLER_FAN_PIN)) - hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); else WRITE(CONTROLLER_FAN_PIN, speed > 0); #endif diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index fda1ba144bc4..1dee0cf7550c 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -41,9 +41,7 @@ extern bool wait_for_user, wait_for_heatup; void quickresume_stepper(); #endif -#if ENABLED(SOFT_RESET_VIA_SERIAL) - void HAL_reboot(); -#endif +void HAL_reboot(); class EmergencyParser { diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 0a4b5114769d..17d790b8cc9a 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -123,7 +123,7 @@ void LEDLights::set_color(const LEDColor &incol // If the pins can do PWM then their intensity will be set. #define _UPDATE_RGBW(C,c) do { \ if (PWM_PIN(RGB_LED_##C##_PIN)) \ - hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ + set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ else \ WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 2840a92c5838..cde2b47d90aa 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -66,10 +66,10 @@ void SpindleLaser::init() { #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); - hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed + set_pwm_duty(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) - hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif #if ENABLED(AIR_EVACUATION) @@ -90,10 +90,10 @@ void SpindleLaser::init() { * @param ocr Power value */ void SpindleLaser::_set_ocr(const uint8_t ocr) { - #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY - hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); + #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); #endif - hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } void SpindleLaser::set_ocr(const uint8_t ocr) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 0415c9c8bb1c..95d60ae48674 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -103,7 +103,7 @@ class SpindleLaser { static void init(); #if ENABLED(MARLIN_DEV_MODE) - static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 807681831723..77c0ccc49b0f 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -126,10 +126,10 @@ void GcodeSuite::M42() { extDigitalWrite(pin, pin_status); #ifdef ARDUINO_ARCH_STM32 - // A simple I/O will be set to 0 by hal.set_pwm_duty() + // A simple I/O will be set to 0 by set_pwm_duty() if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif - hal.set_pwm_duty(pin, pin_status); + set_pwm_duty(pin, pin_status); } #endif // DIRECT_PIN_CONTROL diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 2dd1de00013b..204455e65ec6 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -38,7 +38,7 @@ #include "../sd/cardreader.h" #include "../MarlinCore.h" // for kill -void dump_delay_accuracy_check(); +extern void dump_delay_accuracy_check(); /** * Dn: G-code for development and testing @@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) { for (;;) { /* loop forever (watchdog reset) */ } case 0: - hal.reboot(); + HAL_reboot(); break; case 10: @@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) { settings.reset(); settings.save(); #endif - hal.reboot(); + HAL_reboot(); } break; case 2: { // D2 Read / Write SRAM @@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) { SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); thermalManager.disable_all_heaters(); delay(1000); // Allow time to print - hal.isr_off(); + DISABLE_ISRS(); // Use a low-level delay that does not rely on interrupts to function // Do not spin forever, to avoid thermal risks if heaters are enabled and // watchdog does not work. for (int i = 10000; i--;) DELAY_US(1000UL); - hal.isr_on(); + ENABLE_ISRS(); SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); } break; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 6ee58f769bde..c8ac48f7cff5 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3850,10 +3850,3 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _TEST_PWM #undef _LINEAR_AXES_STR #undef _LOGICAL_AXES_STR - -// JTAG support in the HAL -#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE) - #error "DISABLE_DEBUG is not supported for the selected MCU/Board." -#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE) - #error "DISABLE_JTAG is not supported for the selected MCU/Board." -#endif diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 61db2db9209b..59c74148adef 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -282,9 +282,9 @@ void MarlinUI::init_lcd() { #if PIN_EXISTS(LCD_RESET) // Perform a clean hardware reset with needed delays OUT_WRITE(LCD_RESET_PIN, LOW); - hal.delay_ms(5); + _delay_ms(5); WRITE(LCD_RESET_PIN, HIGH); - hal.delay_ms(5); + _delay_ms(5); u8g.begin(); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 64a65bb6863b..d1a9ba7077fd 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -2149,7 +2149,7 @@ void RebootPrinter() { thermalManager.disable_all_heaters(); planner.finish_and_disable(); DWIN_RebootScreen(); - hal.reboot(); + HAL_reboot(); } void Goto_InfoMenu(){ diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index df6a85780350..7a2cefdd4cea 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1345,7 +1345,7 @@ void Endstops::update() { ES_REPORT_CHANGE(K_MAX); #endif SERIAL_ECHOLNPGM("\n"); - hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); + set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; old_live_state_local = live_state_local; } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 752834c6ab99..45ccdd1702ef 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1264,7 +1264,7 @@ void Planner::recalculate() { #if ENABLED(FAN_SOFT_PWM) #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); #else - #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) @@ -1400,8 +1400,8 @@ void Planner::check_axes_activity() { TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) - TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); - TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); + TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 96d5ba9da837..231efe84e1f2 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -30,7 +30,7 @@ #include "servo.h" -hal_servo_t servo[NUM_SERVOS]; +HAL_SERVO_LIB servo[NUM_SERVOS]; #if ENABLED(EDITABLE_SERVO_ANGLES) uint16_t servo_angles[NUM_SERVOS][2]; diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index cd55a317a275..73dbbdddb729 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -112,5 +112,5 @@ #define MOVE_SERVO(I, P) servo[I].move(P) #define DETACH_SERVO(I) servo[I].detach() -extern hal_servo_t servo[NUM_SERVOS]; +extern HAL_SERVO_LIB servo[NUM_SERVOS]; void servo_init(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 0f47d66791c4..c100051f9808 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1474,7 +1474,7 @@ void Stepper::isr() { #ifndef __AVR__ // Disable interrupts, to avoid ISR preemption while we reprogram the period // (AVR enters the ISR with global interrupts disabled, so no need to do it here) - hal.isr_off(); + DISABLE_ISRS(); #endif // Program timer compare for the maximum period, so it does NOT @@ -1492,7 +1492,7 @@ void Stepper::isr() { hal_timer_t min_ticks; do { // Enable ISRs to reduce USART processing latency - hal.isr_on(); + ENABLE_ISRS(); if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses @@ -1576,7 +1576,7 @@ void Stepper::isr() { * is less than the current count due to something preempting between the * read and the write of the new period value). */ - hal.isr_off(); + DISABLE_ISRS(); /** * Get the current tick value + margin @@ -1611,7 +1611,7 @@ void Stepper::isr() { HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); // Don't forget to finally reenable interrupts - hal.isr_on(); + ENABLE_ISRS(); } #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE @@ -3261,7 +3261,7 @@ void Stepper::report_positions() { #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { case 0: #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 1960dc5d9b52..dccdc55034fd 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -326,7 +326,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) #endif #if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY) + #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) #else #define SET_FAST_PWM_FREQ(P) NOOP #endif @@ -813,7 +813,7 @@ volatile bool Temperature::raw_temps_ready = false; } // Run HAL idle tasks - hal.idletask(); + TERN_(HAL_IDLETASK, HAL_idletask()); // Run UI update TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); @@ -912,7 +912,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _UPDATE_AUTO_FAN(P,D,A) do{ \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ - hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ + set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ else \ WRITE(P##_AUTO_FAN_PIN, D); \ }while(0) @@ -2326,73 +2326,73 @@ void Temperature::init() { TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); - hal.adc_init(); + HAL_adc_init(); #if HAS_TEMP_ADC_0 - hal.adc_enable(TEMP_0_PIN); + HAL_ANALOG_SELECT(TEMP_0_PIN); #endif #if HAS_TEMP_ADC_1 - hal.adc_enable(TEMP_1_PIN); + HAL_ANALOG_SELECT(TEMP_1_PIN); #endif #if HAS_TEMP_ADC_2 - hal.adc_enable(TEMP_2_PIN); + HAL_ANALOG_SELECT(TEMP_2_PIN); #endif #if HAS_TEMP_ADC_3 - hal.adc_enable(TEMP_3_PIN); + HAL_ANALOG_SELECT(TEMP_3_PIN); #endif #if HAS_TEMP_ADC_4 - hal.adc_enable(TEMP_4_PIN); + HAL_ANALOG_SELECT(TEMP_4_PIN); #endif #if HAS_TEMP_ADC_5 - hal.adc_enable(TEMP_5_PIN); + HAL_ANALOG_SELECT(TEMP_5_PIN); #endif #if HAS_TEMP_ADC_6 - hal.adc_enable(TEMP_6_PIN); + HAL_ANALOG_SELECT(TEMP_6_PIN); #endif #if HAS_TEMP_ADC_7 - hal.adc_enable(TEMP_7_PIN); + HAL_ANALOG_SELECT(TEMP_7_PIN); #endif #if HAS_JOY_ADC_X - hal.adc_enable(JOY_X_PIN); + HAL_ANALOG_SELECT(JOY_X_PIN); #endif #if HAS_JOY_ADC_Y - hal.adc_enable(JOY_Y_PIN); + HAL_ANALOG_SELECT(JOY_Y_PIN); #endif #if HAS_JOY_ADC_Z - hal.adc_enable(JOY_Z_PIN); + HAL_ANALOG_SELECT(JOY_Z_PIN); #endif #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif #if HAS_TEMP_ADC_BED - hal.adc_enable(TEMP_BED_PIN); + HAL_ANALOG_SELECT(TEMP_BED_PIN); #endif #if HAS_TEMP_ADC_CHAMBER - hal.adc_enable(TEMP_CHAMBER_PIN); + HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); #endif #if HAS_TEMP_ADC_COOLER - hal.adc_enable(TEMP_COOLER_PIN); + HAL_ANALOG_SELECT(TEMP_COOLER_PIN); #endif #if HAS_TEMP_ADC_PROBE - hal.adc_enable(TEMP_PROBE_PIN); + HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif #if HAS_TEMP_ADC_BOARD - hal.adc_enable(TEMP_BOARD_PIN); + HAL_ANALOG_SELECT(TEMP_BOARD_PIN); #endif #if HAS_TEMP_ADC_REDUNDANT - hal.adc_enable(TEMP_REDUNDANT_PIN); + HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - hal.adc_enable(FILWIDTH_PIN); + HAL_ANALOG_SELECT(FILWIDTH_PIN); #endif #if HAS_ADC_BUTTONS - hal.adc_enable(ADC_KEYPAD_PIN); + HAL_ANALOG_SELECT(ADC_KEYPAD_PIN); #endif #if ENABLED(POWER_MONITOR_CURRENT) - hal.adc_enable(POWER_MONITOR_CURRENT_PIN); + HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN); #endif #if ENABLED(POWER_MONITOR_VOLTAGE) - hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN); + HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); #endif HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); @@ -3333,8 +3333,8 @@ void Temperature::isr() { * This gives each ADC 0.9765ms to charge up. */ #define ACCUMULATE_ADC(obj) do{ \ - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \ - else obj.sample(hal.adc_value()); \ + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \ + else obj.sample(HAL_READ_ADC()); \ }while(0) ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling; @@ -3366,115 +3366,115 @@ void Temperature::isr() { break; #if HAS_TEMP_ADC_0 - case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break; + case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break; case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif #if HAS_TEMP_ADC_BED - case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break; + case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif #if HAS_TEMP_ADC_CHAMBER - case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break; + case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif #if HAS_TEMP_ADC_COOLER - case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break; + case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; #endif #if HAS_TEMP_ADC_PROBE - case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break; + case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif #if HAS_TEMP_ADC_BOARD - case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break; + case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; #endif #if HAS_TEMP_ADC_REDUNDANT - case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break; + case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; #endif #if HAS_TEMP_ADC_1 - case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break; + case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 - case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break; + case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break; case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break; #endif #if HAS_TEMP_ADC_3 - case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break; + case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break; case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break; #endif #if HAS_TEMP_ADC_4 - case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break; + case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break; case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break; #endif #if HAS_TEMP_ADC_5 - case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break; + case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break; case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break; #endif #if HAS_TEMP_ADC_6 - case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break; + case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break; case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break; #endif #if HAS_TEMP_ADC_7 - case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break; + case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break; case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break; + case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break; case Measure_FILWIDTH: - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state - else filwidth.accumulate(hal.adc_value()); + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state + else filwidth.accumulate(HAL_READ_ADC()); break; #endif #if ENABLED(POWER_MONITOR_CURRENT) case Prepare_POWER_MONITOR_CURRENT: - hal.adc_start(POWER_MONITOR_CURRENT_PIN); + HAL_START_ADC(POWER_MONITOR_CURRENT_PIN); break; case Measure_POWER_MONITOR_CURRENT: - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_current_sample(hal.adc_value()); + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_current_sample(HAL_READ_ADC()); break; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) case Prepare_POWER_MONITOR_VOLTAGE: - hal.adc_start(POWER_MONITOR_VOLTAGE_PIN); + HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN); break; case Measure_POWER_MONITOR_VOLTAGE: - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_voltage_sample(hal.adc_value()); + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_voltage_sample(HAL_READ_ADC()); break; #endif #if HAS_JOY_ADC_X - case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break; + case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break; case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break; #endif #if HAS_JOY_ADC_Y - case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break; + case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break; case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break; #endif #if HAS_JOY_ADC_Z - case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break; + case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break; case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break; #endif @@ -3482,12 +3482,12 @@ void Temperature::isr() { #ifndef ADC_BUTTON_DEBOUNCE_DELAY #define ADC_BUTTON_DEBOUNCE_DELAY 16 #endif - case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break; + case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break; case Measure_ADC_KEY: - if (!hal.adc_ready()) + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // redo this state else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) { - raw_ADCKey_value = hal.adc_value(); + raw_ADCKey_value = HAL_READ_ADC(); if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) { NOMORE(current_ADCKey_raw, raw_ADCKey_value); ADCKey_count++; diff --git a/ini/native.ini b/ini/native.ini index eba34afc8394..fe5fe3a5d05a 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -34,14 +34,14 @@ src_filter = ${common.default_src_filter} + [simulator_common] platform = native framework = -build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g +build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} From 7762df7251f1da3be2933670084b416d4a06c89f Mon Sep 17 00:00:00 2001 From: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> Date: Sun, 26 Dec 2021 09:46:13 +0300 Subject: [PATCH 31/32] =?UTF-8?q?=F0=9F=94=A7=20Check=20Chiron=20LCD=20req?= =?UTF-8?q?uirements=20(#23353)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> --- Marlin/src/inc/SanityCheck.h | 14 ++++++++++++++ .../src/lcd/extui/anycubic_chiron/chiron_tft.cpp | 2 +- .../ftdi_eve_touch_ui/generic/about_screen.cpp | 4 ++-- 3 files changed, 17 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c8ac48f7cff5..ab1a6adec560 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2765,6 +2765,20 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Please select only one of CHIRON_TFT_STANDARD or CHIRON_TFT_NEW." #endif +#if ENABLED(ANYCUBIC_LCD_CHIRON) + #if !defined(BEEPER_PIN) + #error "ANYCUBIC_LCD_CHIRON requires BEEPER_PIN" + #elif DISABLED(SDSUPPORT) + #error "ANYCUBIC_LCD_CHIRON requires SDSUPPORT" + #elif TEMP_SENSOR_BED == 0 + #error "ANYCUBIC_LCD_CHIRON requires heatbed (TEMP_SENSOR_BED)" + #elif NONE(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) + #error "ANYCUBIC_LCD_CHIRON requires one of: AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL or MESH_BED_LEVELING" + #elif DISABLED(BABYSTEPPING) + #error "ANYCUBIC_LCD_CHIRON requires BABYSTEPPING" + #endif +#endif + #if EITHER(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) && SD_CONNECTION_IS(LCD) #error "SDCARD_CONNECTION cannot be set to LCD for the enabled TFT. No available SD card reader." #endif diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 9f558e3a9867..6db5972fa70f 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -243,7 +243,7 @@ void ChironTFT::StatusChange(const char * const msg) { case AC_printer_probing: { // If probing completes ok save the mesh and park // Ignore the custom machine name - if (strcmp_P(msg + strlen(CUSTOM_MACHINE_NAME), MARLIN_msg_ready) == 0) { + if (strcmp_P(msg + strlen(MACHINE_NAME), MARLIN_msg_ready) == 0) { injectCommands(F("M500\nG27")); SendtoTFTLN(AC_msg_probing_complete); printer_state = AC_printer_idle; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 6cb85e47c49c..43e5c333651a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -69,8 +69,8 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif draw_text_box(cmd, HEADING_POS, - #ifdef CUSTOM_MACHINE_NAME - F(CUSTOM_MACHINE_NAME) + #ifdef MACHINE_NAME + F(MACHINE_NAME) #else GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) #endif From 56ac68172796d03c15235738fcb234c48167d807 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 26 Dec 2021 03:20:29 -0600 Subject: [PATCH 32/32] =?UTF-8?q?=F0=9F=8E=A8=20Pins=20and=20SDIO=20cleanu?= =?UTF-8?q?p?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../{Sd2Card_sdio_stm32duino.cpp => sdio.cpp} | 10 +- Marlin/src/HAL/STM32/sdio.h | 29 +++ Marlin/src/pins/stm32f4/pins_ANET_ET4.h | 15 +- .../src/pins/stm32f4/pins_BLACK_STM32F407VE.h | 18 +- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 7 - .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 10 - .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 219 +++++++++--------- 7 files changed, 147 insertions(+), 161 deletions(-) rename Marlin/src/HAL/STM32/{Sd2Card_sdio_stm32duino.cpp => sdio.cpp} (98%) create mode 100644 Marlin/src/HAL/STM32/sdio.h diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/sdio.cpp similarity index 98% rename from Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp rename to Marlin/src/HAL/STM32/sdio.cpp index 54e1820c78e6..18b4434dfa73 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -28,6 +28,8 @@ #if ENABLED(SDIO_SUPPORT) +#include "sdio.h" + #include #include @@ -49,14 +51,6 @@ #error "SDIO only supported with STM32F103xE, STM32F103xG, STM32F4xx, or STM32F7xx." #endif -// Fixed -#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 - SD_HandleTypeDef hsd; // create SDIO structure // F4 supports one DMA for RX and another for TX, but Marlin will never // do read and write at same time, so we use the same DMA for both. diff --git a/Marlin/src/HAL/STM32/sdio.h b/Marlin/src/HAL/STM32/sdio.h new file mode 100644 index 000000000000..cf5539c3c76d --- /dev/null +++ b/Marlin/src/HAL/STM32/sdio.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 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 diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index eb3af65f32eb..43aefe97f51d 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -203,19 +203,12 @@ #if ENABLED(SDSUPPORT) - #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 DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif #ifndef SD_DETECT_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index d8a83bef3a89..061680aa79cd 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -140,25 +140,17 @@ // // 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 - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD - - #ifndef SDIO_SUPPORT + #if DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index d1f38f5c8098..e63b534effa5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -338,13 +338,6 @@ #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD - #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_CLOCK 48000000 #define SD_DETECT_PIN PC4 #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 196ca4631998..6d23bc8b208e 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -365,24 +365,14 @@ // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(LCD) - #define SDSS EXP2_07_PIN #define SD_SS_PIN SDSS #define SD_SCK_PIN EXP2_09_PIN #define SD_MISO_PIN EXP2_10_PIN #define SD_MOSI_PIN EXP2_05_PIN #define SD_DETECT_PIN EXP2_04_PIN - #elif SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #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 - #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 7ccb57e2387b..98d222087839 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -48,13 +48,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 PD8 // X_STOP +#define Y_MIN_PIN PD9 // Y_STOP +#define Z_MIN_PIN 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 PD0 // W_STOP +#define Y_MAX_PIN PA8 // V_STOP +#define Z_MAX_PIN PD11 // U_STOP // // Z Probe (when not Z_MIN_PIN) @@ -66,64 +66,64 @@ // // Filament runout // -//#define FIL_RUNOUT_PIN 53 // PA3 BED_THE +//#define FIL_RUNOUT_PIN 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 PE14 // X_PWM +#define X_DIR_PIN PE15 // X_DIR +#define X_ENABLE_PIN PE13 // X_RES +#define X_CS_PIN 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 PB10 // Y_PWM +#define Y_DIR_PIN PE9 // Y_DIR +#define Y_ENABLE_PIN PE10 // Y_RES +#define Y_CS_PIN 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 PC6 // Z_PWM +#define Z_DIR_PIN PC0 // Z_DIR +#define Z_ENABLE_PIN PC15 // Z_RES +#define Z_CS_PIN 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 PD12 // E1_PW +#define E0_DIR_PIN PC13 // E1_DIR +#define E0_ENABLE_PIN PC14 // E1_RE +#define E0_CS_PIN 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 PE5 // E2_PWM +#define E1_DIR_PIN PE6 // E2_DIR +#define E1_ENABLE_PIN PE4 // E2_RESE +#define E1_CS_PIN 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 PB8 // E3_PWM +#define E2_DIR_PIN PE2 // E3_DIR +#define E2_ENABLE_PIN PE3 // E3_RESE +#define E2_CS_PIN 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 PA4 // SPI_CS +#define Y2_CS_PIN PA4 // SPI_CS +#define Z2_CS_PIN PA4 // SPI_CS +#define Z3_CS_PIN PA4 // SPI_CS +#define E3_CS_PIN PA4 // SPI_CS +#define E4_CS_PIN PA4 // SPI_CS +#define E5_CS_PIN 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 PA5 + #define L6470_CHAIN_MISO_PIN PA6 + #define L6470_CHAIN_MOSI_PIN PA7 + #define L6470_CHAIN_SS_PIN PA4 //#define SD_SCK_PIN L6470_CHAIN_SCK_PIN //#define SD_MISO_PIN L6470_CHAIN_MISO_PIN //#define SD_MOSI_PIN L6470_CHAIN_MOSI_PIN #else - //#define SD_SCK_PIN 13 // PB13 SPI_S - //#define SD_MISO_PIN 12 // PB14 SPI_M - //#define SD_MOSI_PIN 11 // PB15 SPI_M + //#define SD_SCK_PIN PB13 // SPI_S + //#define SD_MISO_PIN PB14 // SPI_M + //#define SD_MOSI_PIN PB15 // SPI_M #endif /** @@ -144,114 +144,109 @@ // // 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 PA0 // Analog input 3, digital pin 54 PA0 E1_THERMISTOR +#define TEMP_1_PIN PA1 // Analog input 4, digital pin 55 PA1 E2_THERMISTOR +#define TEMP_2_PIN PA2 // Analog input 5, digital pin 56 PA2 E3_THERMISTOR +#define TEMP_BED_PIN PC2 // Analog input 0, digital pin 51 PC2 BED_THERMISTOR_1 +#define TEMP_BED_1_PIN PC3 // Analog input 1, digital pin 52 PC3 BED_THERMISTOR_2 +#define TEMP_BED_2_PIN PA3 // 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 PC7 // E1_HEAT_PWM +#define HEATER_1_PIN PB0 // E2_HEAT_PWM +#define HEATER_2_PIN PB1 // E3_HEAT_PWM +#define HEATER_BED_PIN PD14 // (BED_HEAT_1 FET +#define HEATER_BED_1_PIN PD13 // (BED_HEAT_2 FET +#define HEATER_BED_2_PIN 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 FAN2_PIN 59 // PE8 E3_FAN PWM pin, Controller fan FET +#define FAN_PIN PC4 // E1_FAN PWM pin, Part cooling fan FET +#define FAN1_PIN PC5 // E2_FAN PWM pin, Extruder fan FET +#define FAN2_PIN PE8 // E3_FAN PWM pin, Controller fan FET #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 58 // FAN1_PIN + #define E0_AUTO_FAN_PIN PC5 // FAN1_PIN #endif // // Misc functions // -#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 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 PA15 // SD_CA +//#define BEEPER_PIN PC9 // SDIO_D1 +//#define LCD_PINS_RS PE9 // Y_DIR +//#define LCD_PINS_ENABLE PE8 // E3_FAN +//#define LCD_PINS_D4 PB12 // SPI_C +//#define LCD_PINS_D5 PB13 // SPI_S +//#define LCD_PINS_D6 PB14 // SPI_M +//#define LCD_PINS_D7 PB15 // SPI_M +//#define BTN_EN1 PC4 // E1_FAN +//#define BTN_EN2 PC5 // E2_FAN +//#define BTN_ENC 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 PB0 //E2_HEAT +//#define EXT1_PIN PB1 //E3_HEAT +//#define EXT2_PIN PB2 //not used (tied to ground +//#define EXT3_PIN PD8 //X_STOP +//#define EXT4_PIN PD9 //Y_STOP +//#define EXT5_PIN PD10 //Z_STOP +//#define EXT6_PIN PD11 +//#define EXT7_PIN PD12 //E1_PW +//#define EXT8_PIN PB10 //Y_PWM // WIFI -// 2 // PD3 CTS -// 3 // PD4 RTS -// 4 // PD5 TX -// 5 // PD6 RX -// 6 // PB5 WIFI_WAKEUP -// 7 // PE11 WIFI_RESET -// 8 // PE12 WIFI_BOOT +// PD3 CTS +// PD4 RTS +// PD5 TX +// PD6 RX +// PB5 WIFI_WAKEUP +// PE11 WIFI_RESET +// PE12 WIFI_BOOT // I2C USER -// 14 // PB7 SDA -// 15 // PB6 SCL +// PB7 SDA +// PB6 SCL // JTAG -// 20 // PA13 JTAG_TMS/SWDIO -// 21 // PA14 JTAG_TCK/SWCLK -// 22 // PB3 JTAG_TDO/SWO +// PA13 JTAG_TMS/SWDIO +// PA14 JTAG_TCK/SWCLK +// PB3 JTAG_TDO/SWO // // 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 - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #ifndef SDIO_SUPPORT + #define SDIO_SUPPORT // Use SDIO for onboard SD + #if DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif + + //#define SD_CARD_DETECT_PIN PA15 // SD_CARD_DETECT + #endif #ifndef SDSS - #define SDSS 16 // PA4 SPI_CS + #define SDSS PA4 // SPI_CS #endif // OTG